hii,
I am getting error while setting navigation stack using rtab map.The is no cmd/vel being published . please help me out with this here are my files base_local_planner.yaml TrajectoryPlannerROS: # Current limits based on AZ3 standalone configuration. acc_lim_x: 0.75 acc_lim_y: 0.75 acc_lim_theta: 4 # 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.5 min_vel_x: 0.24 max_vel_theta: 0.5 min_vel_theta: -0.5 min_in_place_vel_theta: 0.25 holonomic_robot: true xy_goal_tolerance: 0.25 yaw_goal_tolerance: 0.25 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.7 # 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: 10.0 #The robot can move faster when higher. #global planner NavfnROS: allow_unknown: true visualize_potential: false costmap_common_params.yaml obstacle_range: 10 max_obstacle_height: 2.0 raytrace_range: 5.0 footprint: [[ 0.315, 0.4125], [-0.315, 0.32505], [-0.315, -0.32505], [ 0.3, -0.4125]] footprint_padding: 0.03 #robot_radius: ir_of_robot inflation_radius: 0.55 transform_tolerance: 2 controller_patience: 2.0 NavfnROS: allow_unknown: true recovery_behaviors: [ {name: conservative_clear, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: aggressive_clear, type: clear_costmap_recovery/ClearCostmapRecovery} ] conservative_clear: reset_distance: 3.00 aggressive_clear: reset_distance: 1.84 costmap_common_params_2d.yaml footprint: [[ 0.315, 0.4125], [-0.315, 0.32505], [-0.315, -0.32505], [ 0.3, -0.4125]] footprint_padding: 0.04 inflation_layer: inflation_radius: 0.7 # 2xfootprint, it helps to keep the global planned path farther from obstacles transform_tolerance: 2 obstacle_layer: obstacle_range: 5.0 raytrace_range: 5.0 max_obstacle_height: 0.4 track_unknown_space: true observation_sources: laser_scan_sensor point_cloud_sensorA laser_scan_sensor: { data_type: LaserScan, topic: /scan, expected_update_rate: 5.0, marking: true, clearing: true, # observation_persistence: 0.0, # min_obstacle_height: -0.10, # max_obstacle_height: 2.0 } point_cloud_sensorA: { sensor_frame: zed_optical_frame, data_type: PointCloud2, topic: /camera/point_cloud/cloud, expected_update_rate: 5.0, marking: true, clearing: true, min_obstacle_height: -0.10, max_obstacle_height: 2.0 } global_costmap_params.yaml #global_costmap global_frame: map robot_base_frame: base_link 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"} local_costmap_param.yaml global_frame: odom robot_base_frame: base_link update_frequency: 2 publish_frequency: 1 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"} local_costmap_params_2d.yaml global_frame: odom robot_base_frame: base_link update_frequency: 2.0 publish_frequency: 2.0 rolling_window: true width: 5.0 height: 5.0 resolution: 0.025 origin_x: 0.0 origin_y: 0.0 plugins: - {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"} - {name: inflation_layer, type: "costmap_2d::InflationLayer"} obstacle_layer: obstacle_range: 5.0 raytrace_range: 5.0 max_obstacle_height: 0.02 track_unknown_space: true observation_sources: laser_scan_sensor point_cloud_sensorA laser_scan_sensor: { data_type: LaserScan, topic: /scan, expected_update_rate: 0.1, marking: true, clearing: true } point_cloud_sensorA: { sensor_frame: zed_optical_frame, data_type: PointCloud2, topic: /camera/point_cloud/cloud, expected_update_rate: 5.0, marking: true, clearing: true, min_obstacle_height: -99999.0, max_obstacle_height: 99999. } planner_launch file <launch> <group ns="planner"> <node pkg="move_base" type="move_base" respawn="true" name="move_base" output="screen"> <remap from="/ratabmap/odom" to="/planner/odom"/> <remap from="scan" to="/base_scan"/> <remap from="obstacles_cloud" to="/obstacles_cloud"/> <remap from="ground_cloud" to="/ground_cloud"/> <remap from="map" to="/map"/> <remap from="move_base_simple/goal" to="/planner_goal"/> <rosparam file="/home/cair/zed_ws/src/rtabmap_ros/launch/nav_config_2/costmap_common_params_2d.yaml" command="load" ns="global_costmap"/> <rosparam file="/home/cair/zed_ws/src/rtabmap_ros/launch/nav_config_2/costmap_common_params_2d.yaml" command="load" ns="local_costmap" /> <rosparam file="/home/cair/zed_ws/src/rtabmap_ros/launch/nav_config_2/local_costmap_params.yaml" command="load" ns="local_costmap" /> <rosparam file="/home/cair/zed_ws/src/rtabmap_ros/launch/nav_config_2/global_costmap_params.yaml" command="load" ns="global_costmap"/> <rosparam file="/home/cair/zed_ws/src/rtabmap_ros/launch/nav_config_2/base_local_planner_params.yaml" command="load" /> </node> </group> <group ns="camera"> <node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap_ros/data_throttle camera_nodelet_manager"> <remap from="rgb/image_in" to="/camera/rgb/image_rect_color"/> <remap from="depth/image_in" to="/camera/depth/image_rect_color"/> <remap from="rgb/camera_info_in" to="/camera/rgb/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> <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" /> </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"/> </node> </group> </launch> rtabmap ros file <launch> <arg name="stereo" default="false"/> <arg name="rtabmapviz" default="true" /> <arg name="rviz" default="true" /> <arg name="localization" default="false"/> <arg name="cfg" default="" /> <arg name="gui_cfg" default="~/.ros/rtabmap_gui.ini" /> <arg name="rviz_cfg" default="-d $(find rtabmap_ros)/launch/config/rgbd.rviz" /> <arg name="frame_id" default="base_link"/> <arg name="namespace" default="rtabmap"/> <arg name="database_path" default="~/.ros/rtabmap.db"/> <arg name="queue_size" default="20"/> <arg name="wait_for_transform" default="2.0"/> <arg name="rtabmap_args" default="delete_db_on_start"/> <arg name="launch_prefix" default=""/> <arg name="approx_sync" default="true"/> <arg name="rgb_topic" default="/camera/rgb/image_rect_color" /> <arg name="depth_topic" default="/camera/depth/image_rect_color" /> <arg name="camera_info_topic" default="/camera/rgb/camera_info" /> <arg name="rgb_image_transport" default="compressed"/> <arg name="subscribe_scan" default="false"/> <arg name="scan_topic" default="/base_scan"/> <arg name="subscribe_scan_cloud" default="false"/> <arg name="scan_cloud_topic" default="/scan_cloud"/> <arg name="visual_odometry" default="true"/> <arg name="odom_topic" default="/odom"/> <arg name="odom_frame_id" default=""/> <arg name="odom_args" default="$(arg rtabmap_args)"/> <group ns="$(arg namespace)"> <group> <node if="$(arg visual_odometry)" pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen" args="$(arg odom_args)" launch-prefix="$(arg launch_prefix)"> <remap from="rgb/image" to="$(arg rgb_topic)"/> <remap from="depth/image" to="$(arg depth_topic)"/> <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/> </node> </group> <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg rtabmap_args)" launch-prefix="$(arg launch_prefix)"> <remap from="rgb/image" to="$(arg rgb_topic)"/> <remap from="depth/image" to="$(arg depth_topic)"/> <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/> <remap from="goal_out" to="current_goal"/> <remap from="move_base" to="/planner/move_base"/> <remap from="grid_map" to="/map"/> <remap from="scan_cloud" to="$(arg scan_cloud_topic)"/> <remap unless="$(arg visual_odometry)" from="odom" to="$(arg odom_topic)"/> </node> </group> <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="$(arg rviz_cfg)"/> <node if="$(arg rviz)" pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb"> <remap from="rgb/image" to="$(arg rgb_topic)"/> <remap from="depth/image" to="$(arg depth_topic)"/> <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/> <remap from="cloud" to="voxel_cloud" /> </node> </launch> error while launching navigation /camera/data_throttle/decimation: 2 * /camera/data_throttle/rate: 5.0 * /camera/obstacles_detection/frame_id: base_link * /camera/obstacles_detection/map_frame_id: map * /camera/obstacles_detection/max_obstacles_height: 0.4 * /camera/obstacles_detection/min_cluster_size: 20 * /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 * /planner/cmd_vel/abtr_priority: 10 * /planner/move_base/NavfnROS/allow_unknown: True * /planner/move_base/NavfnROS/visualize_potential: False * /planner/move_base/TrajectoryPlannerROS/acc_lim_theta: 4 * /planner/move_base/TrajectoryPlannerROS/acc_lim_x: 0.75 * /planner/move_base/TrajectoryPlannerROS/acc_lim_y: 0.75 * /planner/move_base/TrajectoryPlannerROS/angular_sim_granularity: 0.05 * /planner/move_base/TrajectoryPlannerROS/gdist_scale: 0.8 * /planner/move_base/TrajectoryPlannerROS/holonomic_robot: True * /planner/move_base/TrajectoryPlannerROS/latch_xy_goal_tolerance: True * /planner/move_base/TrajectoryPlannerROS/max_vel_theta: 0.5 * /planner/move_base/TrajectoryPlannerROS/max_vel_x: 0.5 * /planner/move_base/TrajectoryPlannerROS/meter_scoring: True * /planner/move_base/TrajectoryPlannerROS/min_in_place_vel_theta: 0.25 * /planner/move_base/TrajectoryPlannerROS/min_vel_theta: -0.5 * /planner/move_base/TrajectoryPlannerROS/min_vel_x: 0.24 * /planner/move_base/TrajectoryPlannerROS/occdist_scale: 0.01 * /planner/move_base/TrajectoryPlannerROS/pdist_scale: 0.7 * /planner/move_base/TrajectoryPlannerROS/publish_cost_grid_pc: False * /planner/move_base/TrajectoryPlannerROS/sim_granularity: 0.025 * /planner/move_base/TrajectoryPlannerROS/sim_time: 1.5 * /planner/move_base/TrajectoryPlannerROS/vtheta_samples: 20 * /planner/move_base/TrajectoryPlannerROS/vx_samples: 12 * /planner/move_base/TrajectoryPlannerROS/xy_goal_tolerance: 0.25 * /planner/move_base/TrajectoryPlannerROS/yaw_goal_tolerance: 0.25 * /planner/move_base/base_global_planner: navfn/NavfnROS * /planner/move_base/controller_frequency: 10.0 * /planner/move_base/global_costmap/always_send_full_costmap: False * /planner/move_base/global_costmap/footprint: [[0.315, 0.4125],... * /planner/move_base/global_costmap/footprint_padding: 0.04 * /planner/move_base/global_costmap/global_frame: map * /planner/move_base/global_costmap/inflation_layer/inflation_radius: 0.7 * /planner/move_base/global_costmap/obstacle_layer/laser_scan_sensor/clearing: True * /planner/move_base/global_costmap/obstacle_layer/laser_scan_sensor/data_type: LaserScan * /planner/move_base/global_costmap/obstacle_layer/laser_scan_sensor/expected_update_rate: 5.0 * /planner/move_base/global_costmap/obstacle_layer/laser_scan_sensor/marking: True * /planner/move_base/global_costmap/obstacle_layer/laser_scan_sensor/topic: /scan * /planner/move_base/global_costmap/obstacle_layer/max_obstacle_height: 0.4 * /planner/move_base/global_costmap/obstacle_layer/observation_sources: laser_scan_sensor... * /planner/move_base/global_costmap/obstacle_layer/obstacle_range: 5.0 * /planner/move_base/global_costmap/obstacle_layer/point_cloud_sensorA/clearing: True * /planner/move_base/global_costmap/obstacle_layer/point_cloud_sensorA/data_type: PointCloud2 * /planner/move_base/global_costmap/obstacle_layer/point_cloud_sensorA/expected_update_rate: 5.0 * /planner/move_base/global_costmap/obstacle_layer/point_cloud_sensorA/marking: True * /planner/move_base/global_costmap/obstacle_layer/point_cloud_sensorA/max_obstacle_height: 2.0 * /planner/move_base/global_costmap/obstacle_layer/point_cloud_sensorA/min_obstacle_height: -0.1 * /planner/move_base/global_costmap/obstacle_layer/point_cloud_sensorA/sensor_frame: zed_optical_frame * /planner/move_base/global_costmap/obstacle_layer/point_cloud_sensorA/topic: /camera/point_clo... * /planner/move_base/global_costmap/obstacle_layer/raytrace_range: 5.0 * /planner/move_base/global_costmap/obstacle_layer/track_unknown_space: True * /planner/move_base/global_costmap/plugins: [{'type': 'rtabma... * /planner/move_base/global_costmap/publish_frequency: 1 * /planner/move_base/global_costmap/robot_base_frame: base_link * /planner/move_base/global_costmap/transform_tolerance: 2 * /planner/move_base/global_costmap/update_frequency: 1 * /planner/move_base/local_costmap/footprint: [[0.315, 0.4125],... * /planner/move_base/local_costmap/footprint_padding: 0.04 * /planner/move_base/local_costmap/global_frame: odom * /planner/move_base/local_costmap/height: 3.0 * /planner/move_base/local_costmap/inflation_layer/inflation_radius: 0.7 * /planner/move_base/local_costmap/obstacle_layer/laser_scan_sensor/clearing: True * /planner/move_base/local_costmap/obstacle_layer/laser_scan_sensor/data_type: LaserScan * /planner/move_base/local_costmap/obstacle_layer/laser_scan_sensor/expected_update_rate: 5.0 * /planner/move_base/local_costmap/obstacle_layer/laser_scan_sensor/marking: True * /planner/move_base/local_costmap/obstacle_layer/laser_scan_sensor/topic: /scan * /planner/move_base/local_costmap/obstacle_layer/max_obstacle_height: 0.4 * /planner/move_base/local_costmap/obstacle_layer/observation_sources: laser_scan_sensor... * /planner/move_base/local_costmap/obstacle_layer/obstacle_range: 5.0 * /planner/move_base/local_costmap/obstacle_layer/point_cloud_sensorA/clearing: True * /planner/move_base/local_costmap/obstacle_layer/point_cloud_sensorA/data_type: PointCloud2 * /planner/move_base/local_costmap/obstacle_layer/point_cloud_sensorA/expected_update_rate: 5.0 * /planner/move_base/local_costmap/obstacle_layer/point_cloud_sensorA/marking: True * /planner/move_base/local_costmap/obstacle_layer/point_cloud_sensorA/max_obstacle_height: 2.0 * /planner/move_base/local_costmap/obstacle_layer/point_cloud_sensorA/min_obstacle_height: -0.1 * /planner/move_base/local_costmap/obstacle_layer/point_cloud_sensorA/sensor_frame: zed_optical_frame * /planner/move_base/local_costmap/obstacle_layer/point_cloud_sensorA/topic: /camera/point_clo... * /planner/move_base/local_costmap/obstacle_layer/raytrace_range: 5.0 * /planner/move_base/local_costmap/obstacle_layer/track_unknown_space: True * /planner/move_base/local_costmap/origin_x: 0 * /planner/move_base/local_costmap/origin_y: 0 * /planner/move_base/local_costmap/plugins: [{'type': 'costma... * /planner/move_base/local_costmap/publish_frequency: 1 * /planner/move_base/local_costmap/resolution: 0.025 * /planner/move_base/local_costmap/robot_base_frame: base_link * /planner/move_base/local_costmap/rolling_window: True * /planner/move_base/local_costmap/transform_tolerance: 2 * /planner/move_base/local_costmap/update_frequency: 2 * /planner/move_base/local_costmap/width: 3.0 * /rosdistro: indigo * /rosversion: 1.11.20 NODES /camera/ data_throttle (nodelet/nodelet) obstacles_detection (nodelet/nodelet) points_xyz_planner (nodelet/nodelet) /planner/ move_base (move_base/move_base) ROS_MASTER_URI=http://localhost:11311 core service [/rosout] found process[planner/move_base-1]: started with pid [29108] process[camera/data_throttle-2]: started with pid [29109] process[camera/points_xyz_planner-3]: started with pid [29110] process[camera/obstacles_detection-4]: started with pid [29112] [ INFO] [1476964977.905537558]: Using plugin "static_layer" [ INFO] [1476964978.181519481]: Requesting the map... [ INFO] [1476964978.387590702]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964978.486638496]: Received a 107 X 145 map at 0.050000 m/pix [ INFO] [1476964978.495737293]: Using plugin "obstacle_layer" [ INFO] [1476964978.555910524]: Subscribed to Topics: laser_scan_sensor point_cloud_sensorA [ INFO] [1476964978.599178143]: Using plugin "inflation_layer" [ INFO] [1476964978.706693874]: pluginlib WARNING: In file /tmp/binarydeb/ros-indigo-navfn-1.12.12/src/navfn_ros.cpp PLUGINLIB_DECLARE_CLASS is deprecated, please use PLUGINLIB_EXPORT_CLASS instead. You can run the script 'plugin_macro_update' provided with pluginlib in your package source folder to automatically and recursively update legacy macros. Base = base_class_type, Derived = derived_class_type [ INFO] [1476964978.735726182]: Using plugin "obstacle_layer" [ INFO] [1476964978.810067571]: Subscribed to Topics: laser_scan_sensor point_cloud_sensorA [ INFO] [1476964978.869518219]: Using plugin "inflation_layer" [ INFO] [1476964978.988422221]: Created local_planner base_local_planner/TrajectoryPlannerROS [ INFO] [1476964979.001261247]: Sim period is set to 0.10 [ INFO] [1476964979.991212399]: pluginlib WARNING: In file /tmp/binarydeb/ros-indigo-clear-costmap-recovery-1.12.12/src/clear_costmap_recovery.cpp PLUGINLIB_DECLARE_CLASS is deprecated, please use PLUGINLIB_EXPORT_CLASS instead. You can run the script 'plugin_macro_update' provided with pluginlib in your package source folder to automatically and recursively update legacy macros. Base = base_class_type, Derived = derived_class_type [ INFO] [1476964979.994665380]: Recovery behavior will clear layer obstacles [ INFO] [1476964980.051337114]: pluginlib WARNING: In file /tmp/binarydeb/ros-indigo-rotate-recovery-1.12.12/src/rotate_recovery.cpp PLUGINLIB_DECLARE_CLASS is deprecated, please use PLUGINLIB_EXPORT_CLASS instead. You can run the script 'plugin_macro_update' provided with pluginlib in your package source folder to automatically and recursively update legacy macros. Base = base_class_type, Derived = derived_class_type [ INFO] [1476964980.061984842]: Recovery behavior will clear layer obstacles [ INFO] [1476964980.092542546]: Resizing costmap to 107 X 147 at 0.050000 m/pix [ INFO] [1476964980.919452250]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964982.024934940]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964983.012641040]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964983.984434549]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476964985.031318891]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964986.067769286]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964987.176541154]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964988.284935377]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964989.290634837]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476964990.242850059]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964991.394449335]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476964992.332081949]: Resizing costmap to 107 X 147 at 0.050000 m/pix [ INFO] [1476964993.393790149]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964994.482335182]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964995.480345235]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964996.527608326]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964997.544350962]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964998.670003063]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476964999.695018262]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965000.739881147]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965001.804525224]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965002.754938408]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965003.830864638]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476965004.793107210]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965005.884564684]: Resizing costmap to 107 X 147 at 0.050000 m/pix [ INFO] [1476965006.908325272]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476965007.908508296]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965008.985224217]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965010.081895892]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476965011.077050379]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476965012.190715975]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965013.308658571]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476965014.404737725]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965015.475315963]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965016.448837499]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965017.451843079]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ INFO] [1476965018.539765686]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ WARN] [1476965018.674021099]: Illegal bounds change, was [tl: (-0.478373, -3.318025), br: (4.871627, 3.931975)], but is now [tl: (-0.501825, -1.988850), br: (4.846004, 3.876735)]. The offending layer is global_costmap/obstacle_layer [ INFO] [1476965019.507384363]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476965020.550296630]: Resizing costmap to 107 X 147 at 0.050000 m/pix [ WARN] [1476965020.650598350]: Illegal bounds change, was [tl: (-0.478516, -3.435339), br: (4.871484, 3.914661)], but is now [tl: (-0.496089, -1.997612), br: (4.845046, 3.868937)]. The offending layer is global_costmap/obstacle_layer [ INFO] [1476965021.584950000]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ WARN] [1476965021.683805419]: Illegal bounds change, was [tl: (-0.477935, -3.382375), br: (4.872065, 3.917625)], but is now [tl: (-0.492186, -2.201555), br: (4.847005, 3.866617)]. The offending layer is global_costmap/obstacle_layer [ INFO] [1476965022.607655292]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ WARN] [1476965022.698249213]: Illegal bounds change, was [tl: (-0.478719, -3.380401), br: (4.871281, 3.919599)], but is now [tl: (-0.486803, -3.102980), br: (4.846062, 3.860420)]. The offending layer is global_costmap/obstacle_layer [ INFO] [1476965023.681956359]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476965024.657954606]: Resizing costmap to 107 X 146 at 0.050000 m/pix [ INFO] [1476965025.663194502]: Resizing costmap to 107 X 145 at 0.050000 m/pix [ WARN] [1476965025.751626562]: InflationLayer::updateCosts(): seen_ array size is wrong my rqt graph thanks |
Administrator
|
Hi,
They are warnings. Just make sure in RVIZ that the global costmap looks okay. In mapping mode, the global map can change dimension as the robot moves. The "Illegal bounds change" warning seems related to obstacle layer of the global costmap. Maybe the obstacle layer tries to update points outside the static map size. You could comment the obstacle_layer line in global_costmap_params.yaml. You could also set a minimum size of the static map using parameter "grid_size" (in meters) for the rtabmap node cheers, Mathieu |
Free forum by Nabble | Edit this page |