|
@@ -15,7 +15,7 @@
|
|
|
#include <geometry_msgs/Twist.h>
|
|
|
#include <tf/transform_listener.h>
|
|
|
#include <cmath>
|
|
|
-#include "serial_imu_hat_6dof/GetYawData.h"
|
|
|
+#include "serial_imu_hat_6dof/getYawData.h"
|
|
|
#include "ros_arduino_msgs/InfraredSensors.h"
|
|
|
#include "ros_arduino_msgs/GetInfraredDistance.h"
|
|
|
|
|
@@ -36,7 +36,7 @@
|
|
|
//global variable
|
|
|
ros::Publisher twist_pub;
|
|
|
ros::ServiceClient yawSrvClient;
|
|
|
-serial_imu_hat_6dof::GetYawData yawSrv;
|
|
|
+serial_imu_hat_6dof::getYawData yawSrv;
|
|
|
|
|
|
//红外测距相关的服务
|
|
|
ros::ServiceClient distSrvClient;
|
|
@@ -250,7 +250,7 @@ int controlTurn(int flag)
|
|
|
case TURN_LEFT: //向左转动90°
|
|
|
turnFlag = TURN_LEFT;
|
|
|
angular = angular_speed;
|
|
|
- publishTwistCmd(linear_x_speed, 0, 0);
|
|
|
+ publishTwistCmd(linear_x_speed, 0, 0);
|
|
|
check_angle = M_PI/2.0;
|
|
|
break;
|
|
|
|
|
@@ -286,7 +286,7 @@ int controlTurn(int flag)
|
|
|
}else
|
|
|
{
|
|
|
angular = -init_angular_speed;
|
|
|
- check_angle = -check_angle;
|
|
|
+ check_angle = -check_angle;
|
|
|
}
|
|
|
break;
|
|
|
|
|
@@ -379,7 +379,7 @@ void horizMoveMiddle(float tolerance)
|
|
|
}else{
|
|
|
publishTwistCmd(0, -init_linear_y_speed, 0);
|
|
|
}
|
|
|
-
|
|
|
+
|
|
|
}else if(diff > 0) //move left
|
|
|
{
|
|
|
ROS_WARN("move Left horizontally !");
|
|
@@ -389,7 +389,7 @@ void horizMoveMiddle(float tolerance)
|
|
|
publishTwistCmd(0, init_linear_y_speed, 0);
|
|
|
}
|
|
|
}
|
|
|
-
|
|
|
+
|
|
|
|
|
|
distSrvClient.call(distSrv);
|
|
|
now_left = distSrv.response.left_dist;
|
|
@@ -463,7 +463,7 @@ void init_pose_angular(){
|
|
|
begin_yaw = yawSrv.response.yaw;
|
|
|
distSrvClient.call(distSrv);
|
|
|
now_left = distSrv.response.left_dist; //获取左边距离
|
|
|
-
|
|
|
+
|
|
|
controlTurn(TURN_LEFT_10);
|
|
|
distSrvClient.call(distSrv);
|
|
|
next_left = distSrv.response.left_dist; //获取左边距离
|
|
@@ -477,7 +477,7 @@ void init_pose_angular(){
|
|
|
controlTurn(TURN_RIGHT_10);
|
|
|
//turnFlag = HORIZ_MOVE;
|
|
|
//yawUpdate(begin_yaw);
|
|
|
-
|
|
|
+
|
|
|
distSrvClient.call(distSrv);
|
|
|
now_left = distSrv.response.left_dist; //获取左边距离
|
|
|
now_right = distSrv.response.right_dist;//获取右边距离
|
|
@@ -513,7 +513,7 @@ void init_pose_angular(){
|
|
|
* Description: 初始化机器人走迷宫时的位置..
|
|
|
****************************************************************************/
|
|
|
void init_pose_position(){
|
|
|
- float diff = 0.0;
|
|
|
+ float diff = 0.0;
|
|
|
float begin_yaw = 0.0;
|
|
|
float now_front = 0.0;
|
|
|
|
|
@@ -536,7 +536,7 @@ void init_pose_position(){
|
|
|
ROS_WARN("move forward vertically !");
|
|
|
publishTwistCmd(init_linear_x_speed, 0, 0);
|
|
|
}
|
|
|
-
|
|
|
+
|
|
|
|
|
|
distSrvClient.call(distSrv);
|
|
|
now_front = distSrv.response.front_dist;
|
|
@@ -546,7 +546,7 @@ void init_pose_position(){
|
|
|
|
|
|
//当竖直结束后立刻停止移动
|
|
|
publishTwistCmd(0, 0, 0); //stop move
|
|
|
-
|
|
|
+
|
|
|
ros::Duration(0.1).sleep(); //delay 100ms
|
|
|
yawUpdate(begin_yaw); //用于修正转歪的角度
|
|
|
|
|
@@ -570,14 +570,14 @@ void init_pose(){
|
|
|
}
|
|
|
|
|
|
init_pose_angular();
|
|
|
-
|
|
|
+
|
|
|
distSrvClient.call(distSrv);
|
|
|
init_front_dist = distSrv.response.front_dist;
|
|
|
if(fabs(init_front_dist-wall_dist)>tolerance_dist){
|
|
|
init_pose_position();
|
|
|
ROS_WARN("init_pose_position");
|
|
|
}
|
|
|
-
|
|
|
+
|
|
|
}
|
|
|
|
|
|
/*****************************************************************************
|
|
@@ -592,11 +592,11 @@ void infrared_callback(const ros_arduino_msgs::InfraredSensors::ConstPtr& msg)
|
|
|
left_dist = msg->left_dist;
|
|
|
right_dist = msg->right_dist;
|
|
|
|
|
|
-
|
|
|
+
|
|
|
//根据三个传感器反馈的测距值开始移动
|
|
|
checkInfraredDist(front_dist, left_dist, right_dist, tolerance_dist, warn_dist);
|
|
|
yawUpdate(start_yaw_data); //移动完成后开始更新yaw值
|
|
|
-
|
|
|
+
|
|
|
}
|
|
|
|
|
|
/************************************************************
|
|
@@ -635,13 +635,13 @@ int main(int argc, char **argv)
|
|
|
ros::param::get("~init_angular_speed", init_angular_speed);
|
|
|
|
|
|
twist_pub = handle.advertise<geometry_msgs::Twist>(cmd_topic, 1);
|
|
|
- yawSrvClient = handle.serviceClient<serial_imu_hat_6dof::GetYawData>(yaw_service);
|
|
|
+ yawSrvClient = handle.serviceClient<serial_imu_hat_6dof::getYawData>(yaw_service);
|
|
|
distSrvClient = handle.serviceClient<ros_arduino_msgs::GetInfraredDistance>(infrared_service);
|
|
|
-
|
|
|
+
|
|
|
if(init_switch){
|
|
|
init_pose();
|
|
|
}
|
|
|
-
|
|
|
+
|
|
|
ros::Subscriber sub_infrared = handle.subscribe(infrared_topic, 1, infrared_callback);
|
|
|
|
|
|
ros::spin();
|