Browse Source

更新robot_demo中控制小车转圈的程序

corvin rasp melodic 2 years ago
parent
commit
7793270a5a

+ 0 - 2
src/robot_demo/cfg/drive_circle.yaml

@@ -1,5 +1,4 @@
 #####################################################
-#  
 # Description:测试走圆形小程序
 #   angular_speed:角速度.
 #   linear_speed:线速度.
@@ -7,7 +6,6 @@
 # History:
 #   20210512:init this file.
 ######################################################
-
 angular_speed: 0.6
 linear_speed: 0.2
 

+ 8 - 5
src/robot_demo/launch/drive_circle.launch

@@ -1,16 +1,19 @@
 <!--
- * @Author: adam_zhuo
+ * @Author: adam_zhuo,corvin
  * @Date: 2021-04-30 11:16:35
  * @Description: 启动走圆形节点
  * @History: 20210430:初始化文件-adam_zhuo
+ *  20220810:在启动走圆形节点程序前,先启动robot_bringup.launch.
 -->
 <launch>
-
-  <!-- 加载参数 -->
+  <!-- load param -->
   <arg name="cfg_file" default="$(find robot_demo)/cfg/drive_circle.yaml" />
 
-  <!-- 启动drive_circle_node -->
+  <!-- launch robot_bringup -->
+  <include file="$(find robot_bringup)/launch/robot_bringup.launch" />
+
+  <!-- run drive_circle_node -->
   <node pkg="robot_demo" type="robot_demo_drive_circle_node" name="drive_circle_node" output="screen">
     <rosparam file="$(arg cfg_file)" command="load" />
   </node>
-</launch>
+</launch>

+ 8 - 5
src/robot_demo/src/drive_circle_node.cpp

@@ -1,12 +1,13 @@
 /*
- * @Author: adam_zhuo
+ * @Author: adam_zhuo,corvin_zhang
  * @Date: 2021-08-02 14:26:07
  * @Description: file content
  * @History: 20210429:-adam_zhuo
  */
 #include "drive_circle.h"
 
-Drive_Circle::Drive_Circle(){
+Drive_Circle::Drive_Circle()
+{
     ros::param::param<float>("~angular_speed", angular_speed, 0.2);
     ros::param::param<float>("~linear_speed", linear_speed, 0.2);
     _cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
@@ -17,17 +18,19 @@ Drive_Circle::~Drive_Circle(){
 
 }
 
-void Drive_Circle::publish_twist_cmd(float x, float z){
+void Drive_Circle::publish_twist_cmd(float x, float z)
+{
     twist.linear.x = x;
     twist.angular.z = z;
     _cmd_vel_pub.publish(twist);
 }
 
-void Drive_Circle::go(){
+void Drive_Circle::go()
+{
     while (ros::ok())
     {
         publish_twist_cmd(linear_speed, angular_speed);
-        ros::Duration(0.2).sleep();
+        ros::Duration(0.1).sleep();
     }
 }