Hi Mathieu,
I am doing a project, in which the robot will use existing 2D and 3D map to autonomously navigate through the environment. I have successfully be able to create 3D and 2D map using rtabmap. When I drive robot around for making maps, I saw 2D and 3D maps appear on RVIZ. I also check again by using rtabmap-databaseViewer. Everything is ok. However, when I use localization mode of rtabmap, that is, I use existing maps for navigation, the 2D map does not appear on RVIZ. 3D map appears when I click Download map from MapCloud. I have read tutorials and many of your comments, saying that 2D map will automatically appear on RVIZ as soon as robot is able to find relocalize itself. And I am pretty sure that the robot is already able to localize itself when I turn program up, because location of robot in 3D map is correct. I would really appreciate if you know what happens. Here is my RVIZ when I run program I am able to navigate through the map just by clicking 2D Nav goal and click point on the large blue rectangle beneath the 3D map. But when I click somewhere that is not in the blue rectangle, but still in 3D maps, the plan will fail, output the message: The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal. I want to ask if 2D occupancy grid map is used for navigation ?????? I guess that it is used because as far as I know, navigation stack only use 2D map , not 3D. But if it is used, why does it not appear on RVIZ ????? Here is my code <div style="background: #ffffff; overflow:auto;width:auto;border:solid gray;border-width:.1em .1em .1em .8em;padding:.2em .6em;"><pre style="margin: 0; line-height: 125%"><launch> <!-- Localization-only mode --> <arg name="localization" default="false"/> <arg if="$(arg localization)" name="rtabmap_args" default=""/> <arg unless="$(arg localization)" name="rtabmap_args" default="--delete_db_on_start"/> <arg if="$(arg localization)" name="increment_memory" default="false"/> <arg unless="$(arg localization)" name="increment_memory" default="true"/> <arg name="database_path" default="~/.ros/rtabmap.db"/> <!-- Volksbot 3 bringup: launch motors/odometry --> <include file="$(find freenect_launch)/launch/freenect.launch"> <arg name="depth_registration" value="True" /> </include> <include file="$(find lms1xx)launch/LMS1xx.launch"/> <include file="$(find volksbot_driver)launch/volksbot.launch"/> <node pkg="tf" type="static_transform_publisher" name="camera" args="0 0 0 0 0 0 base_link camera_link 100" /> <node pkg="tf" type="static_transform_publisher" name="laser" args="0 0 0 0 0 0 base_link laser 100" /> <!-- teleop --> <include file="$(find turtlebot_teleop)/launch/includes/velocity_smoother.launch.xml"/> <node pkg="turtlebot_teleop" type="turtlebot_teleop_joy" name="turtlebot_teleop_joystick"> <param name="scale_angular" value="0.2"/> <param name="scale_linear" value="0.1"/> <param name="axis_deadman" value="0"/> <param name="axis_linear" value="1"/> <param name="axis_angular" value="0"/> <remap from="turtlebot_teleop_joystick/cmd_vel" to="cmd_vel"/> </node> <node pkg="joy" type="joy_node" name="joystick"/> <!-- HECTOR MAPPING VERSION: use this with ROS bag demo_mapping_no_odom.bag generated --> <!-- Choose visualization --> <arg name="rviz" default="true" /> <arg name="rtabmapviz" default="false" /> <param name="use_sim_time" type="bool" value="false"/> <node pkg="tf" type="static_transform_publisher" name="scanmatcher_to_base_footprint" args="0.0 0.0 0.0 0.0 0.0 0.0 /scanmatcher_frame /base_footprint 100" /> <!-- Odometry from laser scans --> <!-- We use Hector mapping to generate odometry for us --> <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen"> <!-- Frame names --> <param name="map_frame" value="hector_map" /> <param name="base_frame" value="base_footprint" /> <param name="odom_frame" value="odom" /> <!-- Tf use --> <param name="pub_map_odom_transform" value="false"/> <param name="pub_map_scanmatch_transform" value="true"/> <param name="pub_odometry" value="true"/> <!-- Map size / start point --> <param name="map_resolution" value="0.050"/> <param name="map_size" value="2048"/> <param name="map_multi_res_levels" value="2" /> <!-- Map update parameters --> <param name="map_update_angle_thresh" value="0.06" /> <!-- Advertising config --> <param name="scan_topic" value="/scan"/> </node> <group ns="rtabmap"> <!-- SLAM (robot side) --> <!-- args: "delete_db_on_start" and "udebug" --> <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg rtabmap_args)"> <param name="frame_id" type="string" value="base_footprint"/> <param name="subscribe_depth" type="bool" value="true"/> <param name="subscribe_scan" type="bool" value="true"/> <remap from="odom" to="/scanmatch_odom"/> <remap from="scan" to="/scan"/> <remap from="mapData" to="mapData"/> <remap from="rgb/image" to="/camera/rgb/image_rect_color"/> <remap from="depth/image" to="/camera/depth_registered/image_raw"/> <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/> <remap from="goal_out" to="/move_base_simple/goal"/> <remap from="move_base" to="/planner/move_base"/> <remap from="grid_map" to="/rtabmap/grid_map"/> <param name="database_path" type="string" value="$(arg database_path)"/> <!-- RTAB-Map's parameters --> <param name="Reg/Strategy" type="string" value="1"/> <!-- 0=Visual, 1=ICP, 2=Visual+ICP --> <param name="Vis/MaxDepth" type="string" value="10.0"/> <!-- 3D visual words maximum depth 0=infinity --> <param name="Vis/InlierDistance" type="string" value="0.1"/> <!-- 3D visual words correspondence distance --> <param name="Reg/Force3DoF" type="string" value="true"/> <param name="Grid/FromDepth" type="string" value="false"/> <param name="RGBD/OptimizeFromGraphEnd" type="string" value="true"/> <param name="Optimizer/Strategy" type="string" value="0"/> <param name="Kp/DetectorStrategy" type="string" value="0"/> <param name="Kp/MaxFeatures" type="string" value="200"/> <param name="SURF/HessianThreshold" type="string" value="500"/> <param name="Icp/CorrespondenceRatio" type="string" value="0.2"/> <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/> <param name="Mem/IncrementalMemory" type="string" value="$(arg increment_memory)"/> </node> <!-- Visualisation RTAB-Map --> <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen"> <param name="subscribe_depth" type="bool" value="true"/> <param name="subscribe_laserScan" type="bool" value="true"/> <param name="frame_id" type="string" value="base_footprint"/> <remap from="rgb/image" to="/camera/rgb/image_raw"/> <remap from="depth/image" to="/camera/depth_registered/image_raw"/> <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/> <remap from="scan" to="/scan"/> <remap from="odom" to="/scanmatch_odom"/> <param name="rgb/image_transport" type="string" value="compressed"/> <param name="depth/image_transport" type="string" value="compressedDepth"/> </node> </group> <!-- ROS navigation stack move_base --> <remap from="odom" to="/scanmatch_odom"/> <remap from="scan" to="/scan"/> <remap from="obstacles_cloud" to="/obstacles_cloud"/> <remap from="ground_cloud" to="/ground_cloud"/> <remap from="map" to="/rtabmap/grid_map"/> <node pkg="move_base" type="move_base" respawn="true" name="move_base" output="screen"> <param name="base_global_planner" value="navfn/NavfnROS"/> <rosparam file="$(find volksbot_navstack)/costmap_usethis/costmap_common_params_2d.yaml" command="load" ns="global_costmap"/> <rosparam file="$(find volksbot_navstack)/costmap_usethis/costmap_common_params_2d.yaml" command="load" ns="local_costmap" /> <rosparam file="$(find volksbot_navstack)/costmap_usethis/local_costmap_params.yaml" command="load" ns="local_costmap" /> <rosparam file="$(find volksbot_navstack)/costmap_usethis/global_costmap_params.yaml" command="load" ns="global_costmap"/> <rosparam file="$(find volksbot_navstack)/costmap_usethis/base_local_planner_params.yaml" command="load" /> <rosparam file="$(find volksbot_navstack)/costmap_usethis/move_base_params.yaml" command="load" /> </node> <!-- Visualisation RVIZ --> <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_ros)/launch/azimut3/config/azimut3_nav.rviz" output="screen"/> <node pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb"> <remap from="rgb/image" to="/camera/rgb/image_raw"/> <remap from="depth/image" to="/camera/depth_registered/image_raw"/> <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/> <remap from="cloud" to="voxel_cloud" /> <param name="rgb/image_transport" type="string" value="compressed"/> <param name="depth/image_transport" type="string" value="compressedDepth"/> <param name="voxel_size" type="double" value="0.01"/> </node> <!-- Throttling messages --> <group ns="camera"> <node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap_ros/data_throttle camera_nodelet_manager"> <param name="rate" type="double" value="5"/> <param name="decimation" type="int" value="2"/> <remap from="rgb/image_in" to="rgb/image_rect_color"/> <remap from="depth/image_in" to="depth_registered/image_raw"/> <remap from="rgb/camera_info_in" to="depth_registered/camera_info"/> <remap from="rgb/image_out" to="data_resized_image"/> <remap from="depth/image_out" to="data_resized_image_depth"/> <remap from="rgb/camera_info_out" to="data_resized_camera_info"/> </node> <!-- for the planner --> <node pkg="nodelet" type="nodelet" name="points_xyz_planner" args="load rtabmap_ros/point_cloud_xyz camera_nodelet_manager"> <remap from="depth/image" to="data_resized_image_depth"/> <remap from="depth/camera_info" to="data_resized_camera_info"/> <remap from="cloud" to="cloudXYZ" /> <param name="decimation" type="int" value="1"/> <!-- already decimated above --> <param name="max_depth" type="double" value="3.0"/> <param name="voxel_size" type="double" value="0.02"/> </node> <node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_ros/obstacles_detection camera_nodelet_manager"> <remap from="cloud" to="cloudXYZ"/> <remap from="obstacles" to="/obstacles_cloud"/> <remap from="ground" to="/ground_cloud"/> <param name="frame_id" type="string" value="base_footprint"/> <param name="map_frame_id" type="string" value="map"/> <param name="wait_for_transform" type="bool" value="true"/> <param name="Grid/MinClusterSize" type="int" value="20"/> <param name="Grid/MaxObstacleHeight" type="double" value="0.4"/> </node> </group> </launch> </pre></div> I also would like to provide yaml file for move_base, just in case you need some review: global_costmap_params.yaml: <div style="background: #ffffff; overflow:auto;width:auto;border:solid gray;border-width:.1em .1em .1em .8em;padding:.2em .6em;"><pre style="margin: 0; line-height: 125%">#global_costmap global_frame: map robot_base_frame: base_footprint update_frequency: 1 publish_frequency: 1 always_send_full_costmap: false plugins: - {name: static_layer, type: "rtabmap_ros::StaticLayer"} - {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"} - {name: inflation_layer, type: "costmap_2d::InflationLayer"} </pre></div> local_costmap_params.yaml: <div style="background: #ffffff; overflow:auto;width:auto;border:solid gray;border-width:.1em .1em .1em .8em;padding:.2em .6em;"><pre style="margin: 0; line-height: 125%">global_frame: hector_map robot_base_frame: base_footprint update_frequency: 2 publish_frequency: 2 rolling_window: true width: 3.0 height: 3.0 resolution: 0.025 origin_x: 0 origin_y: 0 plugins: - {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"} - {name: inflation_layer, type: "costmap_2d::InflationLayer"} </pre></div> costmap_commons_params_2d.yaml: <div style="background: #ffffff; overflow:auto;width:auto;border:solid gray;border-width:.1em .1em .1em .8em;padding:.2em .6em;"><pre style="margin: 0; line-height: 125%">footprint: [[ 0.31, 0.25], [-0.31, 0.25], [-0.31, -0.25], [ 0.31, -0.25], [0.31, -0.07], [0.46, -0.07], [0.46, 0.07], [0.31, 0.07]] footprint_padding: 0.03 inflation_layer: inflation_radius: 1.1 # 2xfootprint, it helps to keep the global planned path farther from obstacles transform_tolerance: 0.5 cost_scaling_factor: 5.0 obstacle_layer: obstacle_range: 2 raytrace_range: 3 max_obstacle_height: 0.4 track_unknown_space: true observation_sources: laser_scan_sensor point_cloud_sensorA point_cloud_sensorB laser_scan_sensor: { data_type: LaserScan, topic: scan, expected_update_rate: 0.1, marking: true, clearing: true } point_cloud_sensorA: { sensor_frame: base_footprint, data_type: PointCloud2, topic: obstacles_cloud, expected_update_rate: 1.0, marking: true, clearing: true, min_obstacle_height: 0.04 } point_cloud_sensorB: { sensor_frame: base_footprint, data_type: PointCloud2, topic: ground_cloud, expected_update_rate: 1.0, marking: false, clearing: true, min_obstacle_height: -1.0 # make sure the ground is not filtered } </pre></div> base_local_planner_params.yaml: <div style="background: #ffffff; overflow:auto;width:auto;border:solid gray;border-width:.1em .1em .1em .8em;padding:.2em .6em;"><pre style="margin: 0; line-height: 125%">TrajectoryPlannerROS: # Current limits based on AZ3 standalone configuration. acc_lim_x: 0.65 acc_lim_y: 0.65 acc_lim_theta: 1.0 # min_vel_x and max_rotational_vel were set to keep the ICR at # minimal distance of 0.48 m. # Basically, max_rotational_vel * rho_min <= min_vel_x max_vel_x: 0.3 min_vel_x: 0.06 max_vel_theta: 0.1 min_vel_theta: -0.1 min_in_place_vel_theta: 0.2 holonomic_robot: false xy_goal_tolerance: 0.2 yaw_goal_tolerance: 0.2 latch_xy_goal_tolerance: true # make sure that the minimum velocity multiplied by the sim_period is less than twice the tolerance on a goal. Otherwise, the robot will prefer to rotate in place just outside of range of its target position rather than moving towards the goal. sim_time: 1.5 # set between 1 and 2. The higher he value, the smoother the path (though more samples would be required). sim_granularity: 0.025 angular_sim_granularity: 0.05 vx_samples: 12 vtheta_samples: 20 meter_scoring: true pdist_scale: 0.6 # The higher will follow more the global path. gdist_scale: 0.8 occdist_scale: 0.01 publish_cost_grid_pc: false #move_base controller_frequency: 12.0 #The robot can move faster when higher. #global planner NavfnROS: allow_unknown: true visualize_potential: false </pre></div> move_base_params.yaml: <div style="background: #ffffff; overflow:auto;width:auto;border:solid gray;border-width:.1em .1em .1em .8em;padding:.2em .6em;"><pre style="margin: 0; line-height: 125%">controller_frequency: 10.0 controller_patience: 5.0 planner_frequency: 0.0 planner_patience: 5.0 #oscillation_timeout: 10.0 recovery_behavior_enabled: true clearing_rotation_allowed: true recovery_behaviors: - {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery} # - {name: rotate_recovery, type: rotate_recovery/RotateRecovery} # - {name: straf_recovery, type: straf_recovery/StrafRecovery} # - {name: stepback_and_steerturn_recovery, type: stepback_and_steerturn_recovery/StepBackAndSteerTurnRecovery} - {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery} straf_recovery: timeout: 2 minimum_translate_distance: 0.05 maximum_translate_distance: 0.10 straf_vel: 0.05 stepback_and_steerturn_recovery: only_single_steering: true trial_times: 3 obstacle_patience: 0.3 obstacle_check_frequency: 5.0 sim_angle_resolution: 0.1 simulation_frequency: 5 linear_vel_back : -0.1 step_back_length : 0.3 step_back_timeout : 8.0 linear_vel_steer : 0.3 angular_speed_steer : 0.5 turn_angle : 1.5 steering_timeout : 8.0 linear_vel_forward : 0.1 step_forward_length : 1.0 step_forward_timeout: 8.0 </pre></div> roswitha@roswitha:~$ roslaunch volksbot_navstack rtab_hector_nav.launch database_path:="~/catkin_ws/src/volksbot_navstack/rtabmap.db" localization:=true ... logging to /home/roswitha/.ros/log/bd63db2e-7c50-11e8-a65f-3c970eb9cf5e/roslaunch-roswitha-7281.log Checking log directory for disk usage. This may take awhile. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB. xacro: Traditional processing is deprecated. Switch to --inorder processing! To check for compatibility of your document, use option --check-order. For more infos, see http://wiki.ros.org/xacro#Processing_Order xacro.py is deprecated; please use xacro instead started roslaunch server http://10.12.13.220:45855/ SUMMARY ======== PARAMETERS * /camera/camera_nodelet_manager/num_worker_threads: 4 * /camera/data_throttle/decimation: 2 * /camera/data_throttle/rate: 5.0 * /camera/depth_rectify_depth/interpolation: 0 * /camera/depth_registered_rectify_depth/interpolation: 0 * /camera/disparity_depth/max_range: 4.0 * /camera/disparity_depth/min_range: 0.5 * /camera/disparity_registered_hw/max_range: 4.0 * /camera/disparity_registered_hw/min_range: 0.5 * /camera/disparity_registered_sw/max_range: 4.0 * /camera/disparity_registered_sw/min_range: 0.5 * /camera/driver/data_skip: 0 * /camera/driver/debug: False * /camera/driver/depth_camera_info_url: * /camera/driver/depth_frame_id: camera_depth_opti... * /camera/driver/depth_registration: True * /camera/driver/device_id: #1 * /camera/driver/diagnostics_max_frequency: 30.0 * /camera/driver/diagnostics_min_frequency: 30.0 * /camera/driver/diagnostics_tolerance: 0.05 * /camera/driver/diagnostics_window_time: 5.0 * /camera/driver/enable_depth_diagnostics: False * /camera/driver/enable_ir_diagnostics: False * /camera/driver/enable_rgb_diagnostics: False * /camera/driver/rgb_camera_info_url: * /camera/driver/rgb_frame_id: camera_rgb_optica... * /camera/obstacles_detection/Grid/MaxObstacleHeight: 0.4 * /camera/obstacles_detection/Grid/MinClusterSize: 20 * /camera/obstacles_detection/frame_id: base_footprint * /camera/obstacles_detection/map_frame_id: map * /camera/obstacles_detection/wait_for_transform: True * /camera/points_xyz_planner/decimation: 1 * /camera/points_xyz_planner/max_depth: 3.0 * /camera/points_xyz_planner/voxel_size: 0.02 * /hector_mapping/base_frame: base_footprint * /hector_mapping/map_frame: hector_map * /hector_mapping/map_multi_res_levels: 2 * /hector_mapping/map_resolution: 0.05 * /hector_mapping/map_size: 2048 * /hector_mapping/map_update_angle_thresh: 0.06 * /hector_mapping/odom_frame: odom * /hector_mapping/pub_map_odom_transform: False * /hector_mapping/pub_map_scanmatch_transform: True * /hector_mapping/pub_odometry: True * /hector_mapping/scan_topic: /scan * /lms1xx/host: 10.12.184.173 * /move_base/NavfnROS/allow_unknown: True * /move_base/NavfnROS/visualize_potential: False * /move_base/TrajectoryPlannerROS/acc_lim_theta: 1.0 * /move_base/TrajectoryPlannerROS/acc_lim_x: 0.65 * /move_base/TrajectoryPlannerROS/acc_lim_y: 0.65 * /move_base/TrajectoryPlannerROS/angular_sim_granularity: 0.05 * /move_base/TrajectoryPlannerROS/gdist_scale: 0.8 * /move_base/TrajectoryPlannerROS/holonomic_robot: False * /move_base/TrajectoryPlannerROS/latch_xy_goal_tolerance: True * /move_base/TrajectoryPlannerROS/max_vel_theta: 0.1 * /move_base/TrajectoryPlannerROS/max_vel_x: 0.3 * /move_base/TrajectoryPlannerROS/meter_scoring: True * /move_base/TrajectoryPlannerROS/min_in_place_vel_theta: 0.2 * /move_base/TrajectoryPlannerROS/min_vel_theta: -0.1 * /move_base/TrajectoryPlannerROS/min_vel_x: 0.06 * /move_base/TrajectoryPlannerROS/occdist_scale: 0.01 * /move_base/TrajectoryPlannerROS/pdist_scale: 0.6 * /move_base/TrajectoryPlannerROS/publish_cost_grid_pc: False * /move_base/TrajectoryPlannerROS/sim_granularity: 0.025 * /move_base/TrajectoryPlannerROS/sim_time: 1.5 * /move_base/TrajectoryPlannerROS/vtheta_samples: 20 * /move_base/TrajectoryPlannerROS/vx_samples: 12 * /move_base/TrajectoryPlannerROS/xy_goal_tolerance: 0.2 * /move_base/TrajectoryPlannerROS/yaw_goal_tolerance: 0.2 * /move_base/base_global_planner: navfn/NavfnROS * /move_base/clearing_rotation_allowed: True * /move_base/controller_frequency: 10.0 * /move_base/controller_patience: 5.0 * /move_base/global_costmap/always_send_full_costmap: False * /move_base/global_costmap/cost_scaling_factor: 5.0 * /move_base/global_costmap/footprint: [[0.31, 0.25], [-... * /move_base/global_costmap/footprint_padding: 0.03 * /move_base/global_costmap/global_frame: map * /move_base/global_costmap/inflation_layer/inflation_radius: 1.1 * /move_base/global_costmap/obstacle_layer/laser_scan_sensor/clearing: True * /move_base/global_costmap/obstacle_layer/laser_scan_sensor/data_type: LaserScan * /move_base/global_costmap/obstacle_layer/laser_scan_sensor/expected_update_rate: 0.1 * /move_base/global_costmap/obstacle_layer/laser_scan_sensor/marking: True * /move_base/global_costmap/obstacle_layer/laser_scan_sensor/topic: scan * /move_base/global_costmap/obstacle_layer/max_obstacle_height: 0.4 * /move_base/global_costmap/obstacle_layer/observation_sources: laser_scan_sensor... * /move_base/global_costmap/obstacle_layer/obstacle_range: 2 * /move_base/global_costmap/obstacle_layer/point_cloud_sensorA/clearing: True * /move_base/global_costmap/obstacle_layer/point_cloud_sensorA/data_type: PointCloud2 * /move_base/global_costmap/obstacle_layer/point_cloud_sensorA/expected_update_rate: 1.0 * /move_base/global_costmap/obstacle_layer/point_cloud_sensorA/marking: True * /move_base/global_costmap/obstacle_layer/point_cloud_sensorA/min_obstacle_height: 0.04 * /move_base/global_costmap/obstacle_layer/point_cloud_sensorA/sensor_frame: base_footprint * /move_base/global_costmap/obstacle_layer/point_cloud_sensorA/topic: obstacles_cloud * /move_base/global_costmap/obstacle_layer/point_cloud_sensorB/clearing: True * /move_base/global_costmap/obstacle_layer/point_cloud_sensorB/data_type: PointCloud2 * /move_base/global_costmap/obstacle_layer/point_cloud_sensorB/expected_update_rate: 1.0 * /move_base/global_costmap/obstacle_layer/point_cloud_sensorB/marking: False * /move_base/global_costmap/obstacle_layer/point_cloud_sensorB/min_obstacle_height: -1.0 * /move_base/global_costmap/obstacle_layer/point_cloud_sensorB/sensor_frame: base_footprint * /move_base/global_costmap/obstacle_layer/point_cloud_sensorB/topic: ground_cloud * /move_base/global_costmap/obstacle_layer/raytrace_range: 3 * /move_base/global_costmap/obstacle_layer/track_unknown_space: True * /move_base/global_costmap/plugins: [{'type': 'rtabma... * /move_base/global_costmap/publish_frequency: 1 * /move_base/global_costmap/robot_base_frame: base_footprint * /move_base/global_costmap/transform_tolerance: 0.5 * /move_base/global_costmap/update_frequency: 1 * /move_base/local_costmap/cost_scaling_factor: 5.0 * /move_base/local_costmap/footprint: [[0.31, 0.25], [-... * /move_base/local_costmap/footprint_padding: 0.03 * /move_base/local_costmap/global_frame: hector_map * /move_base/local_costmap/height: 3.0 * /move_base/local_costmap/inflation_layer/inflation_radius: 1.1 * /move_base/local_costmap/obstacle_layer/laser_scan_sensor/clearing: True * /move_base/local_costmap/obstacle_layer/laser_scan_sensor/data_type: LaserScan * /move_base/local_costmap/obstacle_layer/laser_scan_sensor/expected_update_rate: 0.1 * /move_base/local_costmap/obstacle_layer/laser_scan_sensor/marking: True * /move_base/local_costmap/obstacle_layer/laser_scan_sensor/topic: scan * /move_base/local_costmap/obstacle_layer/max_obstacle_height: 0.4 * /move_base/local_costmap/obstacle_layer/observation_sources: laser_scan_sensor... * /move_base/local_costmap/obstacle_layer/obstacle_range: 2 * /move_base/local_costmap/obstacle_layer/point_cloud_sensorA/clearing: True * /move_base/local_costmap/obstacle_layer/point_cloud_sensorA/data_type: PointCloud2 * /move_base/local_costmap/obstacle_layer/point_cloud_sensorA/expected_update_rate: 1.0 * /move_base/local_costmap/obstacle_layer/point_cloud_sensorA/marking: True * /move_base/local_costmap/obstacle_layer/point_cloud_sensorA/min_obstacle_height: 0.04 * /move_base/local_costmap/obstacle_layer/point_cloud_sensorA/sensor_frame: base_footprint * /move_base/local_costmap/obstacle_layer/point_cloud_sensorA/topic: obstacles_cloud * /move_base/local_costmap/obstacle_layer/point_cloud_sensorB/clearing: True * /move_base/local_costmap/obstacle_layer/point_cloud_sensorB/data_type: PointCloud2 * /move_base/local_costmap/obstacle_layer/point_cloud_sensorB/expected_update_rate: 1.0 * /move_base/local_costmap/obstacle_layer/point_cloud_sensorB/marking: False * /move_base/local_costmap/obstacle_layer/point_cloud_sensorB/min_obstacle_height: -1.0 * /move_base/local_costmap/obstacle_layer/point_cloud_sensorB/sensor_frame: base_footprint * /move_base/local_costmap/obstacle_layer/point_cloud_sensorB/topic: ground_cloud * /move_base/local_costmap/obstacle_layer/raytrace_range: 3 * /move_base/local_costmap/obstacle_layer/track_unknown_space: True * /move_base/local_costmap/origin_x: 0 * /move_base/local_costmap/origin_y: 0 * /move_base/local_costmap/plugins: [{'type': 'costma... * /move_base/local_costmap/publish_frequency: 2 * /move_base/local_costmap/resolution: 0.025 * /move_base/local_costmap/robot_base_frame: base_footprint * /move_base/local_costmap/rolling_window: True * /move_base/local_costmap/transform_tolerance: 0.5 * /move_base/local_costmap/update_frequency: 2 * /move_base/local_costmap/width: 3.0 * /move_base/planner_frequency: 0.0 * /move_base/planner_patience: 5.0 * /move_base/recovery_behavior_enabled: True * /move_base/recovery_behaviors: [{'type': 'clear_... * /move_base/stepback_and_steerturn_recovery/angular_speed_steer: 0.5 * /move_base/stepback_and_steerturn_recovery/linear_vel_back: -0.1 * /move_base/stepback_and_steerturn_recovery/linear_vel_forward: 0.1 * /move_base/stepback_and_steerturn_recovery/linear_vel_steer: 0.3 * /move_base/stepback_and_steerturn_recovery/obstacle_check_frequency: 5.0 * /move_base/stepback_and_steerturn_recovery/obstacle_patience: 0.3 * /move_base/stepback_and_steerturn_recovery/only_single_steering: True * /move_base/stepback_and_steerturn_recovery/sim_angle_resolution: 0.1 * /move_base/stepback_and_steerturn_recovery/simulation_frequency: 5 * /move_base/stepback_and_steerturn_recovery/steering_timeout: 8.0 * /move_base/stepback_and_steerturn_recovery/step_back_length: 0.3 * /move_base/stepback_and_steerturn_recovery/step_back_timeout: 8.0 * /move_base/stepback_and_steerturn_recovery/step_forward_length: 1.0 * /move_base/stepback_and_steerturn_recovery/step_forward_timeout: 8.0 * /move_base/stepback_and_steerturn_recovery/trial_times: 3 * /move_base/stepback_and_steerturn_recovery/turn_angle: 1.5 * /move_base/straf_recovery/maximum_translate_distance: 0.1 * /move_base/straf_recovery/minimum_translate_distance: 0.05 * /move_base/straf_recovery/straf_vel: 0.05 * /move_base/straf_recovery/timeout: 2 * /points_xyzrgb/depth/image_transport: compressedDepth * /points_xyzrgb/rgb/image_transport: compressed * /points_xyzrgb/voxel_size: 0.01 * /robot_description: <?xml version="1.... * /rosdistro: kinetic * /rosversion: 1.12.13 * /rtabmap/rtabmap/Grid/FromDepth: false * /rtabmap/rtabmap/Icp/CorrespondenceRatio: 0.2 * /rtabmap/rtabmap/Kp/DetectorStrategy: 0 * /rtabmap/rtabmap/Kp/MaxFeatures: 200 * /rtabmap/rtabmap/Mem/IncrementalMemory: false * /rtabmap/rtabmap/Optimizer/Strategy: 0 * /rtabmap/rtabmap/RGBD/OptimizeFromGraphEnd: true * /rtabmap/rtabmap/RGBD/ProximityPathMaxNeighbors: 10 * /rtabmap/rtabmap/Reg/Force3DoF: true * /rtabmap/rtabmap/Reg/Strategy: 1 * /rtabmap/rtabmap/SURF/HessianThreshold: 500 * /rtabmap/rtabmap/Vis/InlierDistance: 0.1 * /rtabmap/rtabmap/Vis/MaxDepth: 10.0 * /rtabmap/rtabmap/database_path: ~/catkin_ws/src/v... * /rtabmap/rtabmap/frame_id: base_footprint * /rtabmap/rtabmap/subscribe_depth: True * /rtabmap/rtabmap/subscribe_scan: True * /teleop_velocity_smoother/accel_lim_v: 1.0 * /teleop_velocity_smoother/accel_lim_w: 2.0 * /teleop_velocity_smoother/decel_factor: 1.5 * /teleop_velocity_smoother/frequency: 20.0 * /teleop_velocity_smoother/robot_feedback: 2 * /teleop_velocity_smoother/speed_lim_v: 0.8 * /teleop_velocity_smoother/speed_lim_w: 5.4 * /turtlebot_teleop_joystick/axis_angular: 0 * /turtlebot_teleop_joystick/axis_deadman: 0 * /turtlebot_teleop_joystick/axis_linear: 1 * /turtlebot_teleop_joystick/scale_angular: 0.2 * /turtlebot_teleop_joystick/scale_linear: 0.1 * /use_sim_time: False NODES /camera/ camera_nodelet_manager (nodelet/nodelet) data_throttle (nodelet/nodelet) depth_metric (nodelet/nodelet) depth_metric_rect (nodelet/nodelet) depth_points (nodelet/nodelet) depth_rectify_depth (nodelet/nodelet) depth_registered_hw_metric_rect (nodelet/nodelet) depth_registered_metric (nodelet/nodelet) depth_registered_rectify_depth (nodelet/nodelet) depth_registered_sw_metric_rect (nodelet/nodelet) disparity_depth (nodelet/nodelet) disparity_registered_hw (nodelet/nodelet) disparity_registered_sw (nodelet/nodelet) driver (nodelet/nodelet) ir_rectify_ir (nodelet/nodelet) obstacles_detection (nodelet/nodelet) points_xyz_planner (nodelet/nodelet) points_xyzrgb_hw_registered (nodelet/nodelet) points_xyzrgb_sw_registered (nodelet/nodelet) register_depth_rgb (nodelet/nodelet) rgb_debayer (nodelet/nodelet) rgb_rectify_color (nodelet/nodelet) rgb_rectify_mono (nodelet/nodelet) /rtabmap/ rtabmap (rtabmap_ros/rtabmap) / camera (tf/static_transform_publisher) camera_base_link (tf2_ros/static_transform_publisher) camera_base_link1 (tf2_ros/static_transform_publisher) camera_base_link2 (tf2_ros/static_transform_publisher) camera_base_link3 (tf2_ros/static_transform_publisher) hector_mapping (hector_mapping/hector_mapping) joystick (joy/joy_node) laser (tf/static_transform_publisher) lms1xx (lms1xx/LMS1xx_node) move_base (move_base/move_base) points_xyzrgb (nodelet/nodelet) robot_state_publisher (robot_state_publisher/robot_state_publisher) rviz (rviz/rviz) scanmatcher_to_base_footprint (tf/static_transform_publisher) teleop_velocity_smoother (nodelet/nodelet) turtlebot_teleop_joystick (turtlebot_teleop/turtlebot_teleop_joy) volksbot (volksbot_driver/volksbot) auto-starting new master process[master]: started with pid [7294] ROS_MASTER_URI=http://10.12.13.220:11311 setting /run_id to bd63db2e-7c50-11e8-a65f-3c970eb9cf5e process[rosout-1]: started with pid [7307] started core service [/rosout] process[camera/camera_nodelet_manager-2]: started with pid [7325] process[camera/driver-3]: started with pid [7326] process[camera/rgb_debayer-4]: started with pid [7327] process[camera/rgb_rectify_mono-5]: started with pid [7333] process[camera/rgb_rectify_color-6]: started with pid [7346] process[camera/ir_rectify_ir-7]: started with pid [7362] process[camera/depth_rectify_depth-8]: started with pid [7377] process[camera/depth_metric_rect-9]: started with pid [7390] [ INFO] [1530354686.393928953]: Initializing nodelet with 4 worker threads. process[camera/depth_metric-10]: started with pid [7416] process[camera/depth_points-11]: started with pid [7429] process[camera/register_depth_rgb-12]: started with pid [7443] process[camera/points_xyzrgb_sw_registered-13]: started with pid [7455] process[camera/depth_registered_sw_metric_rect-14]: started with pid [7471] [ INFO] [1530354686.444805352]: Number devices connected: 1 [ INFO] [1530354686.444869461]: 1. device on bus 000:00 is a Xbox NUI Camera (2ae) from Microsoft (45e) with serial id 'A70777V01080228A' process[camera/depth_registered_rectify_depth-15]: started with pid [7486] [ INFO] [1530354686.456866439]: Searching for device with index = 1 process[camera/points_xyzrgb_hw_registered-16]: started with pid [7495] process[camera/depth_registered_hw_metric_rect-17]: started with pid [7510] process[camera/depth_registered_metric-18]: started with pid [7519] process[camera/disparity_depth-19]: started with pid [7530] process[camera/disparity_registered_sw-20]: started with pid [7550] process[camera/disparity_registered_hw-21]: started with pid [7561] process[camera_base_link-22]: started with pid [7581] process[camera_base_link1-23]: started with pid [7599] process[camera_base_link2-24]: started with pid [7615] process[camera_base_link3-25]: started with pid [7630] process[lms1xx-26]: started with pid [7640] process[robot_state_publisher-27]: started with pid [7649] process[volksbot-28]: started with pid [7669] process[camera-29]: started with pid [7680] process[laser-30]: started with pid [7699] process[teleop_velocity_smoother-31]: started with pid [7715] process[turtlebot_teleop_joystick-32]: started with pid [7733] process[joystick-33]: started with pid [7748] process[scanmatcher_to_base_footprint-34]: started with pid [7765] process[hector_mapping-35]: started with pid [7784] process[rtabmap/rtabmap-36]: started with pid [7802] process[move_base-37]: started with pid [7808] process[rviz-38]: started with pid [7819] process[points_xyzrgb-39]: started with pid [7827] process[camera/data_throttle-40]: started with pid [7831] process[camera/points_xyz_planner-41]: started with pid [7851] process[camera/obstacles_detection-42]: started with pid [7870] [ERROR] [1530354686.795187532]: Couldn't open joystick /dev/input/js0. Will retry every second. [ INFO] [1530354686.844637945]: Starting node... [ INFO] [1530354686.846734274]: rviz version 1.12.16 [ INFO] [1530354686.846793359]: compiled against Qt version 5.5.1 [ INFO] [1530354686.846825859]: compiled against OGRE version 1.9.0 (Ghadamon) [ INFO] [1530354686.917624351]: Initializing nodelet with 8 worker threads. HectorSM map lvl 0: cellLength: 0.05 res x:2048 res y: 2048 HectorSM map lvl 1: cellLength: 0.1 res x:1024 res y: 1024 [ INFO] [1530354687.028897541]: HectorSM p_base_frame_: base_footprint [ INFO] [1530354687.029099950]: HectorSM p_map_frame_: hector_map [ INFO] [1530354687.029436520]: HectorSM p_odom_frame_: odom [ INFO] [1530354687.029675210]: HectorSM p_scan_topic_: /scan [ INFO] [1530354687.029896288]: HectorSM p_use_tf_scan_transformation_: true [ INFO] [1530354687.030098082]: HectorSM p_pub_map_odom_transform_: false [ INFO] [1530354687.030123796]: HectorSM p_scan_subscriber_queue_size_: 5 [ INFO] [1530354687.030226552]: HectorSM p_map_pub_period_: 2.000000 [ INFO] [1530354687.030336259]: HectorSM p_update_factor_free_: 0.400000 [ INFO] [1530354687.030417076]: HectorSM p_update_factor_occupied_: 0.900000 [ INFO] [1530354687.030438893]: HectorSM p_map_update_distance_threshold_: 0.400000 [ INFO] [1530354687.030558111]: HectorSM p_map_update_angle_threshold_: 0.060000 [ INFO] [1530354687.030632255]: HectorSM p_laser_z_min_value_: -1.000000 [ INFO] [1530354687.030704360]: HectorSM p_laser_z_max_value_: 1.000000 [ INFO] [1530354687.194258240]: Stereo is NOT SUPPORTED [ INFO] [1530354687.194382292]: OpenGl version: 3 (GLSL 1.3). [ INFO] [1530354687.474752600]: /rtabmap/rtabmap(maps): map_filter_radius = 0.000000 [ INFO] [1530354687.474801318]: /rtabmap/rtabmap(maps): map_filter_angle = 30.000000 [ INFO] [1530354687.474835243]: /rtabmap/rtabmap(maps): map_cleanup = true [ INFO] [1530354687.474875030]: /rtabmap/rtabmap(maps): map_negative_poses_ignored = true [ INFO] [1530354687.474903339]: /rtabmap/rtabmap(maps): map_negative_scan_ray_tracing = true [ INFO] [1530354687.474929818]: /rtabmap/rtabmap(maps): cloud_output_voxelized = true [ INFO] [1530354687.474957378]: /rtabmap/rtabmap(maps): cloud_subtract_filtering = false [ INFO] [1530354687.474991044]: /rtabmap/rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2 [ INFO] [1530354687.483884900]: /rtabmap/rtabmap(maps): octomap_tree_depth = 16 [ INFO] [1530354687.540840012]: rtabmap: frame_id = base_footprint [ INFO] [1530354687.540885431]: rtabmap: map_frame_id = map [ INFO] [1530354687.540904588]: rtabmap: tf_delay = 0.050000 [ INFO] [1530354687.540930645]: rtabmap: tf_tolerance = 0.100000 [ INFO] [1530354687.540955720]: rtabmap: odom_sensor_sync = false [ INFO] [1530354687.760723695]: Setting RTAB-Map parameter "Grid/FromDepth"="false" [ INFO] [1530354687.820092971]: Setting RTAB-Map parameter "Icp/CorrespondenceRatio"="0.2" [ INFO] [1530354687.870237593]: Setting RTAB-Map parameter "Kp/DetectorStrategy"="0" [ INFO] [1530354687.891288322]: Setting RTAB-Map parameter "Kp/MaxFeatures"="200" [ INFO] [1530354687.939047094]: Setting RTAB-Map parameter "Mem/IncrementalMemory"="false" [ INFO] [1530354688.209660584]: Setting RTAB-Map parameter "Optimizer/Strategy"="0" [ INFO] [1530354688.251151699]: Setting RTAB-Map parameter "RGBD/OptimizeFromGraphEnd"="true" [ INFO] [1530354688.281923830]: Setting RTAB-Map parameter "RGBD/ProximityPathMaxNeighbors"="10" [ INFO] [1530354688.287753754]: Setting RTAB-Map parameter "Reg/Force3DoF"="true" [ INFO] [1530354688.290478514]: Setting RTAB-Map parameter "Reg/Strategy"="1" Property::loadValue() TODO: error handling - unexpected QVariant type 0. [ INFO] [1530354688.386503226]: Setting RTAB-Map parameter "SURF/HessianThreshold"="500" [ INFO] [1530354688.408651602]: Rate=5.000000 Hz [ INFO] [1530354688.408711880]: Decimation=2 [ INFO] [1530354688.408742540]: Approximate time sync = true [ INFO] [1530354688.709981469]: Setting RTAB-Map parameter "Vis/InlierDistance"="0.1" [ INFO] [1530354688.720112669]: Setting RTAB-Map parameter "Vis/MaxDepth"="10.0" [ INFO] [1530354688.730189426]: Approximate time sync = true [ INFO] [1530354689.436920174]: Setting "Grid/RangeMax" parameter to 0 (default 5.000000) as "subscribe_scan" or "subscribe_scan_cloud" is true. [ INFO] [1530354689.441465389]: Update RTAB-Map parameter "Mem/UseOdomFeatures"="false" from database [ INFO] [1530354689.470725728]: obstacles_detection: Setting parameter "Grid/MaxObstacleHeight"="0.4" [ INFO] [1530354689.473902392]: obstacles_detection: Setting parameter "Grid/MinClusterSize"="20" [ INFO] [1530354689.772782427]: RTAB-Map detection rate = 1.000000 Hz [ INFO] [1530354689.772930177]: rtabmap: Using database from "/home/roswitha/catkin_ws/src/volksbot_navstack/rtabmap.db" (282 MB). [ INFO] [1530354691.519248214]: rtabmap: 2D occupancy grid map loaded. [ INFO] [1530354691.519831284]: rtabmap: Database version = "0.17.3". [ INFO] [1530354691.555944399]: /rtabmap/rtabmap: queue_size = 10 [ INFO] [1530354691.555988771]: /rtabmap/rtabmap: rgbd_cameras = 1 [ INFO] [1530354691.556016547]: /rtabmap/rtabmap: approx_sync = true [ INFO] [1530354691.556088737]: Setup depth callback [ INFO] [1530354691.599706152]: /rtabmap/rtabmap subscribed to (approx sync): /scanmatch_odom, /camera/rgb/image_rect_color, /camera/depth_registered/image_raw, /camera/rgb/camera_info, /scan [ INFO] [1530354691.612535133]: rtabmap 0.17.3 started... [ WARN] [1530354692.117568758]: Timed out waiting for transform from base_footprint to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.100757 timeout was 0.1. [ INFO] [1530354692.161322924]: Starting a 3s RGB and Depth stream flush. [ INFO] [1530354692.161558366]: Opened 'Xbox NUI Camera' on bus 0:0 with serial number 'A70777V01080228A' [ WARN] [1530354692.597352267]: Could not find any compatible depth output mode for 1. Falling back to default depth output mode 1. [ INFO] [1530354692.610859635]: rgb_frame_id = 'camera_rgb_optical_frame' [ INFO] [1530354692.610927699]: depth_frame_id = 'camera_depth_optical_frame' [ WARN] [1530354692.622722082]: Camera calibration file /home/roswitha/.ros/camera_info/rgb_A70777V01080228A.yaml not found. [ WARN] [1530354692.622985720]: Using default parameters for RGB camera calibration. [ WARN] [1530354692.623248373]: Camera calibration file /home/roswitha/.ros/camera_info/depth_A70777V01080228A.yaml not found. [ WARN] [1530354692.623423254]: Using default parameters for IR camera calibration. [ WARN] (2018-06-30 12:31:34.216) Rtabmap.cpp:994::process() Update map correction based on last localization saved in database! correction = xyz=0.010760,0.007926,0.000000 rpy=0.000000,0.000000,-0.005287, nearest id = 26 of last pose = xyz=0.009041,0.002464,0.000000 rpy=0.000000,0.000000,-0.002377, odom = xyz=-0.001690,-0.005470,0.000000 rpy=0.000000,-0.000000,0.002910 [ INFO:0] Initialize OpenCL runtime... [ WARN] (2018-06-30 12:31:34.353) Rtabmap.cpp:1920::process() Rejected loop closure 30 -> 804: Not enough inliers 18/20 (matches=31) between 30 and 804 [ WARN] [1530354694.485938690]: Many occupancy grids should be loaded (~577), this may take a while to update the map(s)... [ INFO] [1530354694.653466788]: Using plugin "static_layer" [ INFO] [1530354695.141878950]: Requesting the map... [ WARN] [1530354695.259226597]: Map(s) updated! (0.773443 s) [ INFO] [1530354695.261548914]: rtabmap (804): Rate=1.00s, Limit=0.000s, RTAB-Map=0.2438s, Maps update=0.8002s pub=0.0016s (local map=577, WM=577) [ INFO] [1530354695.281012507]: Creating 1 swatches [ INFO] [1530354695.285111999]: Stopping device RGB and Depth stream flush. [ INFO] [1530354695.346428196]: Resizing costmap to 185 X 364 at 0.050000 m/pix [ INFO] [1530354695.445403865]: Received a 185 X 364 map at 0.050000 m/pix [ INFO] [1530354695.451558942]: Using plugin "obstacle_layer" [ INFO] [1530354695.472342597]: Subscribed to Topics: laser_scan_sensor point_cloud_sensorA point_cloud_sensorB [ INFO] [1530354695.553864188]: Using plugin "inflation_layer" [ WARN] [1530354695.610822584]: The scan observation buffer has not been updated for 0.13 seconds, and it should be updated every 0.10 seconds. [ INFO] [1530354695.643160363]: Using plugin "obstacle_layer" [ INFO] [1530354695.646826665]: Subscribed to Topics: laser_scan_sensor point_cloud_sensorA point_cloud_sensorB [ INFO] [1530354695.727834098]: Using plugin "inflation_layer" [ WARN] [1530354695.780159772]: The scan observation buffer has not been updated for 0.12 seconds, and it should be updated every 0.10 seconds. [ INFO] [1530354695.805618671]: Created local_planner base_local_planner/TrajectoryPlannerROS [ INFO] [1530354695.820213610]: Sim period is set to 0.10 [ WARN] [1530354696.610809859]: The scan observation buffer has not been updated for 1.13 seconds, and it should be updated every 0.10 seconds. [ WARN] [1530354696.610857628]: The obstacles_cloud observation buffer has not been updated for 1.10 seconds, and it should be updated every 1.00 seconds. [ WARN] [1530354696.780241511]: The scan observation buffer has not been updated for 1.12 seconds, and it should be updated every 0.10 seconds. [ WARN] [1530354696.780301033]: The obstacles_cloud observation buffer has not been updated for 1.09 seconds, and it should be updated every 1.00 seconds. [ INFO] [1530354696.794136970]: Recovery behavior will clear layer obstacles [ INFO] [1530354696.796992275]: Recovery behavior will clear layer obstacles [ INFO] [1530354696.860910762]: odom received! [ INFO] [1530354697.086307249]: rtabmap (805): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1856s, Maps update=0.0346s pub=0.0005s (local map=577, WM=577) [ INFO] [1530354697.086547176]: Resizing costmap to 184 X 365 at 0.050000 m/pix [ INFO] [1530354697.229817665]: Creating 1 swatches [ INFO] [1530354698.341526388]: rtabmap (806): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1941s, Maps update=0.0392s pub=0.0005s (local map=577, WM=577) [ INFO] [1530354698.341613179]: Resizing costmap to 182 X 365 at 0.050000 m/pix [ INFO] [1530354698.506728335]: Creating 1 swatches [ INFO] [1530354699.569617571]: rtabmap (807): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1593s, Maps update=0.0257s pub=0.0005s (local map=577, WM=577) [ INFO] [1530354699.569745514]: Resizing costmap to 182 X 365 at 0.050000 m/pix [ INFO] [1530354700.767878194]: Resizing costmap to 184 X 365 at 0.050000 m/pix [ INFO] [1530354700.771395364]: rtabmap (808): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1739s, Maps update=0.0333s pub=0.0040s (local map=577, WM=577) [ INFO] [1530354700.917670753]: Creating 1 swatches [ INFO] [1530354701.918004274]: Resizing costmap to 181 X 365 at 0.050000 m/pix [ INFO] [1530354701.918004678]: rtabmap (809): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1679s, Maps update=0.0344s pub=0.0005s (local map=577, WM=577) [ INFO] [1530354702.049818906]: Creating 1 swatches [ INFO] [1530354703.104275297]: rtabmap (810): Rate=1.00s, Limit=0.000s, RTAB-Map=0.2070s, Maps update=0.0358s pub=0.0003s (local map=577, WM=577) [ INFO] [1530354703.104446373]: Resizing costmap to 182 X 365 at 0.050000 m/pix [ INFO] [1530354703.248805258]: Creating 1 swatches [ INFO] [1530354704.271465364]: Resizing costmap to 182 X 365 at 0.050000 m/pix [ INFO] [1530354704.274411289]: rtabmap (811): Rate=1.00s, Limit=0.000s, RTAB-Map=0.2143s, Maps update=0.0328s pub=0.0033s (local map=577, WM=577) [ INFO] [1530354705.525346028]: Resizing costmap to 182 X 365 at 0.050000 m/pix [ INFO] [1530354705.525356758]: rtabmap (812): Rate=1.00s, Limit=0.000s, RTAB-Map=0.2182s, Maps update=0.0361s pub=0.0005s (local map=577, WM=577) [ INFO] [1530354707.110437629]: Resizing costmap to 184 X 365 at 0.050000 m/pix [ INFO] [1530354707.110447232]: rtabmap (813): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1919s, Maps update=0.0337s pub=0.0007s (local map=577, WM=577) [ INFO] [1530354707.256015445]: Creating 1 swatches [ INFO] [1530354708.255108372]: rtabmap (814): Rate=1.00s, Limit=0.000s, RTAB-Map=0.1844s, Maps upd |
Administrator
|
Hi,
When using move_base, only the 2D map is used for navigation. In your case, the 2D map is built from laser scans. If you open database viewer and show the GraphView, can you see the grid map assembled? Something like this: If not, there is something wrong with the local map creation from the laser scans. |
Hi Matthieu,
Yes, The 2D map is there when I open GraphView However, I am not be able to display the 2D map on Rviz. The 3D map is fine, and the robot works fine, i.e it is able to use the "hidden" 2D map to navigate through the environment. Is there something wrong with the latest version of Rtabmap ? Also, when I draw a new map, is there any way I can know the coordinate of each location on the map in Rviz ? |
In reply to this post by matlabbe
Hi Matthieu,
I want to add a little information about my case. So when I start rtabmap, I got a message like this : MapsManager.cpp:497::updateMapCaches() Occupancy grid for location 804 should be added to global map (e..g, a ROS node is subscribed to any occupancy grid output) but it cannot be found in memory. For convenience, the occupancy grid is regenerated. Make sure parameter "RGBD/CreateOccupancyGrid" is true to avoid this warning for the next locations added to map. For older locations already in database without an occupancy grid map, you can use the "rtabmap-databaseViewer" to regenerate the missing occupancy grid maps and save them back in the database for next sessions. This warning is only shown once. Does that relate anything to my problem of not generating 2D occupancy grid map ? |
Administrator
|
Can you share the database? I could try to see if it can be shown in rviz on my setup. Not sure why you have the updateMapCaches() warning as local occupancy grids seem in the database. To see the actual node's pose on the map, you may launch rtabmapviz and show the graph view, you will then be able to mouse over the nodes and see the positions. In rviz, you would have to create your own markers, by subscribing to /rtabmap/mapGraph.
cheers, Mathieu |
Dear Matthieu,
After some time I have figured out the problem of not displaying the 2D map. I try to draw a large map of the whole building by drawing many small maps and using multi mapping session. However, as I turn on the robot with existing map to continue to draw next map, the old map disappear, and I got a message like : Discard all existing pose as loop closure detection fail. I guess this is the reason why my existing 2D map does not exist, as RTAB map automatically discard old 2D maps. I also seen some error relating to optimize from graph end. I set this Optimizing from graph end to false. Does it cause my problem ? Do you know how I can fix my problem ? My second problem is that map created by RTAB Map seems to have a lot of noise. For locations that robot have already seen, when I go back to that location, RTAB Map also update it, resulting in overlapping obstacle in the map. When I use Hector Slam, the map is very clean. I would appreciate if you could tell my how I can improve the performance of RTAB Map. |
In reply to this post by matlabbe
One more problem is that, when I click "Download map" from MapCloud in Rviz, the computer get stucked after loading all these 3D cloud. I doubt that computer does not have enough power to deal with such clouds ? Do I need to change some parameter so that computer does not get stuck any more ???? Based on these difficulties, I guess that RTAB Map is helpful if our focus is mainly 3D Map. Can we use it reliably with 2D Map and for navigation ??? |
Administrator
|
What is exactly the warning message telling it is discarding all previous poses? so I can see where in the code it happens.
If you start a new session, it is the default behavior that the previous map is not shown, as the current pose is not linked to a previous map. If there is a loop closure with a previous map at some point, that old map should re-appear. If you don't want to clear the previous map if the robot cannot localize on the first frame, you can set the parameter Rtabmap/StartNewMapOnLoopClosure to true. When your computer is "stuck", it is because RVIZ is creating all point clouds after downloading all data. You should wait until RVIZ has generated all of them. Actually, RTAB-Map has been used (here) a lot more with 2D navigation than 3D navigation. I did more tests to replicate your bug of empty grid map and I did! Thx to point out the RGBD/OptimizeFromGraphEnd parameter. There was a bug when this parameter was true. This is now fixed in this commit. Without updating the code or if you want to re-use a previous database, we can also set use_saved_map to false to make sure all local occupancy grids are correctly loaded: <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap"> <param name="use_saved_map" type="bool" value="false"/> ... </node> cheers, Mathieu |
Free forum by Nabble | Edit this page |