Browse Source

更新robot_demo中走正方形的代码,将odom_combined坐标变换更新为odom

corvin rasp melodic 2 năm trước cách đây
mục cha
commit
25820b6dcc

+ 1 - 1
src/robot_demo/cfg/drive_square.yaml

@@ -7,7 +7,7 @@
 # History:
 #   20210512:init this file.
 ######################################################
-odom_frame: /odom_combined
+odom_frame: /odom
 base_frame: /base_footprint
 
 square_side_length: 0.4

+ 1 - 1
src/robot_demo/launch/drive_square.launch

@@ -1,5 +1,5 @@
 <!--
- * @Author: adam_zhuo,corvin_zhang
+ * @Author:corvin_zhang
  * @Date: 2021-04-30 11:16:35
  * @Description: 启动走正方形节点
  * @History: 20210430:初始化文件-adam_zhuo

+ 5 - 5
src/robot_demo/src/drive_square_node.cpp

@@ -9,16 +9,16 @@
 Drive_Square::Drive_Square()
 {
     ros::param::param<std::string>("~odom_frame", odom_frame, "odom");
-    ros::param::param<std::string>("~base_frame", base_frame, "base_link");
-    ros::param::param<float>("~angular_speed", angular_speed, 0.2);
-    ros::param::param<float>("~linear_speed", linear_speed, 0.2);
+    ros::param::param<std::string>("~base_frame", base_frame, "base_footprint");
+    ros::param::param<float>("~angular_speed", angular_speed, 0.6);
+    ros::param::param<float>("~linear_speed",  linear_speed,  0.2);
     ros::param::param<float>("~square_side_length", square_side_length, 0.4);
     _cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
     go();
 }
 
-Drive_Square::~Drive_Square(){
-
+Drive_Square::~Drive_Square()
+{
 }
 
 void Drive_Square::publish_twist_cmd(float x, float z)

+ 0 - 59
src/robot_navigation/launch/hector_mapping.launch

@@ -1,59 +0,0 @@
-<!--
-  Author: corvin
-  Description: hector mapping.
-  History:
-    20180601: initial this file.
--->
-<launch>
-  <arg name="map_scanmatch_frame_name" default="scanmatcher_frame"/>
-  <arg name="pub_map_odom_transform"   default="true"/>
-  <arg name="scan_queue_size"          default="10"/>
-  <arg name="base_frame" default="/base_link" />
-  <arg name="odom_frame" default="/odom" />
-  <arg name="map_frame" default="/map" />
-  <arg name="scan_topic" default="/scan" />
-  <arg name="map_size"   default="512" />
-
-  <!-- startup ydlidar -->
-  <include file="$(find ydlidar)/launch/lidar.launch" />
-
-  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
-    <!-- Frame names -->
-    <param name="map_frame" value="$(arg map_frame)" />
-    <param name="base_frame" value="$(arg base_frame)" />
-    <param name="odom_frame" value="$(arg odom_frame)" />
-
-    <!-- Map resolution/size/start point -->
-    <param name="map_resolution" value="0.04"/>
-    <param name="map_size"       value="$(arg map_size)"/>
-    <param name="map_start_x"    value="0.2" />
-    <param name="map_start_y"    value="0.2" />
-
-    <!-- Map update parameters -->
-    <param name="map_update_distance_thresh" value="0.45" />
-    <param name="map_update_angle_thresh"    value="0.30" />
-    <param name="map_pub_period"             value="2.2" />
-    <param name="map_multi_res_levels"       value="2" />
-    <param name="update_factor_free"         value="0.4" />
-    <param name="update_factor_occupied"     value="0.9" />
-
-    <!-- lidar laser parameters -->
-    <param name="scan_topic"         value="$(arg scan_topic)" />
-    <param name="laser_min_dist"     value="0.06" />
-    <param name="laser_max_dist"     value="4.09" />
-    <param name="laser_z_min_value"  value="-1.0" />
-    <param name="laser_z_max_value"  value="1.0" />
-
-    <param name="output_timing"              value="false"/>
-    <param name="scan_subscriber_queue_size" value="$(arg scan_queue_size)"/>
-    <param name="pub_map_odom_transform"     value="$(arg pub_map_odom_transform)"/>
-
-    <param name="advertise_map_service"      value="true" />
-    <param name="use_tf_scan_transformation" value="true" />
-    <param name="use_tf_pose_start_estimate" value="true" />
-    <param name="tf_map_scanmatch_transform_frame_name" value="$(arg map_scanmatch_frame_name)" />
-  </node>
-
-  <node pkg="tf" type="static_transform_publisher" name="map_to_odom" args="0.0 0.0 0.0 0 0 0.0 /map /odom 100"/>
-</launch>
-

+ 0 - 4
src/robot_navigation/launch/hector_mapping_view.launch

@@ -1,4 +0,0 @@
-<launch>
-   <!-- startup rviz to show hector mapping process -->
-  <node name="rviz" type="rviz" pkg="rviz" args="-d $(find robot_navigation)/rviz/hector_view.rviz" />
-</launch>

+ 48 - 6
src/robot_navigation/rviz/view_navigation.rviz

@@ -51,19 +51,61 @@ Visualization Manager:
       Reference Frame: <Fixed Frame>
       Value: true
     - Class: rviz/TF
-      Enabled: false
+      Enabled: true
       Frame Timeout: 15
       Frames:
         All Enabled: true
+        back_wheel_link:
+          Value: true
+        base_footprint:
+          Value: true
+        base_imu_link:
+          Value: true
+        base_link:
+          Value: true
+        front_wheel_link:
+          Value: true
+        left_wheel_link:
+          Value: true
+        lidar:
+          Value: true
+        map:
+          Value: true
+        odom:
+          Value: true
+        right_wheel_link:
+          Value: true
+        servo_left_right_link:
+          Value: true
+        servo_up_down_link:
+          Value: true
       Marker Scale: 0.6000000238418579
       Name: TF
       Show Arrows: true
       Show Axes: true
       Show Names: true
       Tree:
-        {}
+        map:
+          odom:
+            base_footprint:
+              base_link:
+                back_wheel_link:
+                  {}
+                base_imu_link:
+                  {}
+                front_wheel_link:
+                  {}
+                left_wheel_link:
+                  {}
+                lidar:
+                  {}
+                right_wheel_link:
+                  {}
+                servo_left_right_link:
+                  servo_up_down_link:
+                    {}
       Update Interval: 0
-      Value: false
+      Value: true
     - Alpha: 0.800000011920929
       Class: rviz/Map
       Color Scheme: map
@@ -387,7 +429,7 @@ Window Geometry:
   Height: 697
   Hide Left Dock: true
   Hide Right Dock: true
-  QMainWindow State: 000000ff00000000fd0000000400000000000001820000037dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000440000037d000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000254fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004400000254000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004d400000044fc0100000002fb0000000800540069006d00650000000000000004d40000048d00fffffffb0000000800540069006d00650100000000000004500000000000000000000003dc0000025400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd00000004000000000000018200000254fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000004400000254000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000254fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004400000254000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004d400000044fc0100000002fb0000000800540069006d00650000000000000004d40000048d00fffffffb0000000800540069006d00650100000000000004500000000000000000000003dc0000025400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
@@ -397,5 +439,5 @@ Window Geometry:
   Views:
     collapsed: true
   Width: 988
-  X: 150
-  Y: 160
+  X: 133
+  Y: 157