Pārlūkot izejas kodu

Follow googlecartographer/cartographer_ros#360. (#57)

Wolfgang Hess 8 gadi atpakaļ
vecāks
revīzija
b33c15d112

+ 2 - 1
cartographer_turtlebot/cartographer_turtlebot/flat_world_imu_node_main.cc

@@ -41,7 +41,8 @@ int main(int argc, char** argv) {
             // The 'imu_data_raw' topic of the Kobuki base will at times publish
             // IMU messages out of order. These out of order messages must be
             // dropped.
-            if (last_published_time.isZero() || imu_in->header.stamp > last_published_time) {
+            if (last_published_time.isZero() ||
+                imu_in->header.stamp > last_published_time) {
               last_published_time = imu_in->header.stamp;
               sensor_msgs::Imu imu_out = *imu_in;
               // TODO(damonkohler): This relies on the z-axis alignment of the

+ 8 - 0
cartographer_turtlebot/configuration_files/demo_turtlebot.rviz

@@ -259,6 +259,14 @@ Visualization Manager:
       Use Fixed Frame: true
       Use rainbow: true
       Value: true
+    - Class: rviz/MarkerArray
+      Enabled: true
+      Marker Topic: /trajectory_nodes_list
+      Name: MarkerArray
+      Namespaces:
+        "": true
+      Queue Size: 100
+      Value: true
   Enabled: true
   Global Options:
     Background Color: 100; 100; 100

+ 1 - 0
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_2d.lua

@@ -30,6 +30,7 @@ options = {
   lookup_transform_timeout_sec = 0.2,
   submap_publish_period_sec = 0.3,
   pose_publish_period_sec = 5e-3,
+  trajectory_publish_period_sec = 30e-3,
 }
 
 MAP_BUILDER.use_trajectory_builder_2d = true

+ 1 - 0
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_3d.lua

@@ -30,6 +30,7 @@ options = {
   lookup_transform_timeout_sec = 0.2,
   submap_publish_period_sec = 0.3,
   pose_publish_period_sec = 5e-3,
+  trajectory_publish_period_sec = 30e-3,
 }
 
 MAP_BUILDER.use_trajectory_builder_3d = true

+ 1 - 0
cartographer_turtlebot/configuration_files/turtlebot_urg_lidar_2d.lua

@@ -30,6 +30,7 @@ options = {
   lookup_transform_timeout_sec = 0.2,
   submap_publish_period_sec = 0.3,
   pose_publish_period_sec = 5e-3,
+  trajectory_publish_period_sec = 30e-3,
 }
 
 MAP_BUILDER.use_trajectory_builder_2d = true