Browse Source

解决编译异常问题,将GetYawData改为getYawData解决

corvin rasp melodic 2 years ago
parent
commit
2a429ce97c

+ 0 - 15
src/infrared_maze/CMakeLists.txt

@@ -61,14 +61,12 @@ find_package(catkin REQUIRED COMPONENTS
 # add_service_files(
 #   FILES
 #   Service1.srv
-#   Service2.srv
 # )
 
 ## Generate actions in the 'action' folder
 # add_action_files(
 #   FILES
 #   Action1.action
-#   Action2.action
 # )
 
 ## Generate added messages and services with any dependencies listed here
@@ -80,7 +78,6 @@ find_package(catkin REQUIRED COMPONENTS
 ################################################
 ## Declare ROS dynamic reconfigure parameters ##
 ################################################
-
 ## To declare and build dynamic reconfigure parameters within this
 ## package, follow these steps:
 ## * In the file package.xml:
@@ -94,7 +91,6 @@ find_package(catkin REQUIRED COMPONENTS
 ## Generate dynamic reconfigure parameters in the 'cfg' folder
 # generate_dynamic_reconfigure_options(
 #   cfg/DynReconf1.cfg
-#   cfg/DynReconf2.cfg
 # )
 
 ###################################
@@ -124,11 +120,6 @@ include_directories(
  ${catkin_INCLUDE_DIRS}
 )
 
-## Declare a C++ library
-# add_library(${PROJECT_NAME}
-#   src/${PROJECT_NAME}/infrared_maze.cpp
-# )
-
 ## Add cmake target dependencies of the library
 ## as an example, code may need to be generated before libraries
 ## either from message generation or dynamic reconfigure
@@ -139,12 +130,6 @@ include_directories(
 ## The recommended prefix ensures that target names across packages don't collide
 add_executable(${PROJECT_NAME}_node src/infrared_maze.cpp)
 
-## Rename C++ executable without prefix
-## The above recommended prefix causes long target names, the following renames the
-## target back to the shorter version for ease of user use
-## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
-# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
-
 ## Add cmake target dependencies of the executable
 ## same as for the library above
 add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

+ 18 - 18
src/infrared_maze/src/infrared_maze.cpp

@@ -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();

+ 25 - 25
src/robot_dynamic/src/robot_dynamic.cpp

@@ -13,8 +13,8 @@
 #include <tf/transform_listener.h>
 #include <dynamic_reconfigure/server.h>
 #include <robot_dynamic/dynamicConfig.h>
-#include "serial_imu_hat_6dof/GetYawData.h"
- 
+#include "serial_imu_hat_6dof/getYawData.h"
+
 using namespace std;
 
 #define VERTICAL_MOVE  1
@@ -25,7 +25,7 @@ string yaw_service = "/imu_node/GetYawData";
 
 ros::Publisher twist_pub;
 ros::ServiceClient yawSrvClient;
-serial_imu_hat_6dof::GetYawData yawSrv;
+serial_imu_hat_6dof::getYawData yawSrv;
 
 string odomFrame = "/odom_combined";
 string baseFrame = "/base_footprint";
@@ -38,15 +38,15 @@ float vertical_dist = 0.0;
 float horizon_dist = 0.0;
 int log_level= 0;
 
-float tolerance_dist = 0.005; 
+float tolerance_dist = 0.005;
 float start_yaw = 0.0;
 
- 
+
 /**
  * @description: 发布控制移动的消息,这里对于平面移动的
  *   机器人只需要控制linear_x,linear_y和angular_z即可.
- * @param {type} 
- * @return {type} 
+ * @param {type}
+ * @return {type}
  */
 void publishTwistCmd(float linear_x, float linear_y, float angular_z)
 {
@@ -65,9 +65,9 @@ void publishTwistCmd(float linear_x, float linear_y, float angular_z)
 
 
 /**
- * @description:控制小车转指定度数 
- * @param {float}角度值 
- * @return {void} 
+ * @description:控制小车转指定度数
+ * @param {float}角度值
+ * @return {void}
  */
 void yawUpdate(const float dynamic_turn_angle)
 {
@@ -76,7 +76,7 @@ void yawUpdate(const float dynamic_turn_angle)
     float angular = 0.0;
     float now_yaw = 0.0;
     float turn_yaw = 0.0;
-    
+
     turn_yaw = dynamic_turn_angle/180*M_PI;
     target = start_yaw + turn_yaw;
     if(target > M_PI){
@@ -84,7 +84,7 @@ void yawUpdate(const float dynamic_turn_angle)
     }else if(target < -M_PI){
         target = target + M_PI*2.0;
     }
-    
+
     //开始不断的计算偏差,调整角度
     while(fabs(diff) > 0.01)
     {
@@ -113,7 +113,7 @@ void yawUpdate(const float dynamic_turn_angle)
 /**
  * @description: 控制小车竖直水平运动指定距离
  * @param {int}水平竖直flag,{float}运动距离
- * @return {void} 
+ * @return {void}
  */
 void robot_move(int move_flag,const float check_dist)
 {
@@ -147,7 +147,7 @@ void robot_move(int move_flag,const float check_dist)
                 publishTwistCmd(0,copysign(linear_y_speed,check_dist), 0);
                 break;
         }
-            
+
         ros::Duration(0.10).sleep(); //100 ms
 
         tf_Listener.lookupTransform(odomFrame, baseFrame, ros::Time(0),tf_Transform);
@@ -165,8 +165,8 @@ void robot_move(int move_flag,const float check_dist)
 
 /**
  * @description: 动态修改参数回调函数
- * @param {type} 
- * @return {type} 
+ * @param {type}
+ * @return {type}
  */
 void dynamic_callback(robot_dynamic::dynamicConfig &config)
 {
@@ -176,7 +176,7 @@ void dynamic_callback(robot_dynamic::dynamicConfig &config)
             config.angular_z_speed,
             config.turn_angle,
             config.log_level);
- 
+
     linear_x_speed  = config.linear_x_speed;
     linear_y_speed  = config.linear_y_speed;
     angular_z_speed = config.angular_z_speed;
@@ -194,27 +194,27 @@ void dynamic_callback(robot_dynamic::dynamicConfig &config)
         horizon_dist = config.horizon_dist;
     }
 }
- 
- 
+
+
 int main(int argc, char **argv)
 {
     ros::init(argc, argv, "robot_dynamic_node");
     ros::NodeHandle handle;
- 
+
     ros::param::get("~odomFrame", odomFrame);
 
     dynamic_reconfigure::Server<robot_dynamic::dynamicConfig> server;
     dynamic_reconfigure::Server<robot_dynamic::dynamicConfig>::CallbackType callback;
- 
+
     callback = boost::bind(&dynamic_callback, _1);
     server.setCallback(callback);
- 
+
     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);
     yawSrvClient.call(yawSrv);
     start_yaw = yawSrv.response.yaw;
     ROS_INFO("start_yaw is %f",start_yaw);
-    
+
     ros::spin();
     return 0;
-}
+}