Question regarding path planning

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

Question regarding path planning

Kaiglz
Hello, everyone, I am currently working on navigation by using the grid map and the localisation of RTABMAP.
So far everything works, I get the costmaps with the corresponding data when I drive around outside. I use a 24-layer lidar and an RGBD camera .
My question refers to the planning of the route. When I publish a 2D NavGoal via RViz to /rtabmap/goal , the route planning is topological planned over the previously driven route and then bends at the end. (see picture)
Picture 1
How do I make it possible to plan a route using the local and global cost map instead of topological planning?
In order to get a smoother route. Do you have any suggestions or ideas?
My launch file:
<launch>  
  <!-- <node pkg="tf" type="static_transform_publisher" name="odom_to_base" args="0 0 0 0 0 0 odom base_link 0.1" />  -->
  <node pkg="tf" type="static_transform_publisher" name="odom_to_carrier" args="0 0 1 0 0.0 0 base_link carrier_link 0.1" />  
  <node pkg="tf" type="static_transform_publisher" name="carrier_to_camera" args="0 0.3 0 0 0.0 0 carrier_link camera_link 0.1" /> 
  <node pkg="tf" type="static_transform_publisher" name="carrier_to_laser" args="0 0 0.3 0 0.0 3.14159265359 carrier_link laser 0.1" />
<!-- ############################################################################################################ -->


 <node name="pointcloud_to_depthimage" pkg="rtabmap_ros" type="pointcloud_to_depthimage">
    <remap from="cloud"            to="scan_cloud"/>
    <!--<remap from="image"            to="/camera/color/image_raw"> -->
    <remap from="camera_info"      to="/camera/color/camera_info"/>
   
<!--    <param name="wait_for_transform"               value="0.2"/>
    <param name="fixed_frame_id"   type="string"   value="odom"/> -->
    <param name="decimation"       type="int"      value="1"/>
    <param name="fill_holes_size"  type="int"      value="20"/>
  </node> 


<!-- ############################################################################################################ -->
<!--RTABMAP Launch -->    
<!-- ############################################################################################################ -->

  <!-- Choose between RGB-D and stereo -->      
  <arg name="stereo"          	      value="false"/>
 
  <!-- Choose visualization -->
  <arg name="rtabmapviz"              value="false" /> 
  <arg name="rviz"                    value="true" />
  
  <!-- Localization-only mode -->
  <arg name="localization"            value="true"/>
  
  <!-- sim time for convenience, if playing a rosbag -->
  <arg name="use_sim_time"            value="true"/>
  <param if="$(arg use_sim_time)" name="use_sim_time" value="true"/>
  
  <!-- Corresponding config files -->
  <arg name="cfg"                     value="" /> <!-- To change RTAB-Map's parameters, set the path of config file (*.ini) generated by the standalone app -->
  <arg name="gui_cfg"                 value="~/.ros/2020-07-07-Schmal/mrs6_realsense/rtabmap_gui.ini"/>
  <arg name="rviz_cfg"                value="$(find rtabmap_ros)/launch/config/rgbd.rviz" />
  
  <arg name="frame_id"                value="base_link"/>     <!-- Fixed frame id, you may set "base_link" or "base_footprint" if they are published -->
  <arg name="odom_frame_id"           value="odom"/>                <!-- If set, TF is used to get odometry instead of the topic -->
  <arg name="map_frame_id"            value="map"/>
  <arg name="ground_truth_frame_id"   value=""/>     <!-- e.g., "world" -->
  <arg name="ground_truth_base_frame_id" value=""/>  <!-- e.g., "tracker", a fake frame matching the frame "frame_id" (but on different TF tree) -->
  <arg name="namespace"               value="rtabmap"/>
  <arg name="database_path"           value="~/.ros/2020-07-21-14-54-06.db"/>
  <arg name="queue_size"              value="10"/>
  <arg name="wait_for_transform"      value="0.3"/>
  <arg name="args"                    value=""/>              <!-- delete_db_on_start, udebug - -delete_db_on_start-->
  <arg name="rtabmap_args"            value="$(arg args)"/>   <!-- deprecated, use "args" argument -->
  <arg name="launch_prefix"           value=""/>              <!-- for debugging purpose, it fills launch-prefix tag of the nodes -->
  <arg name="output"                  value="screen"/>        <!-- Control node output (screen or log) -->
  <arg name="publish_tf_map"          value="true"/>


  <!-- if timestamps of the input topics are synchronized using approximate or exact time policy-->
  <arg     if="$(arg stereo)" name="approx_sync"  value="false"/>
  <arg unless="$(arg stereo)" name="approx_sync"  value="true"/>         
   
  <!-- RGB-D related topics -->
  <arg name="rgb_topic"                value="/camera/color/image_raw"/>
  <arg name="depth_topic"              value="/image_raw"/>
  <arg name="camera_info_topic"        value="/camera/color/camera_info"/>
  <arg name="depth_camera_info_topic"  value="/camera/color/camera_info"/>
  
  <!-- stereo related topics -->
  <arg name="stereo_namespace"        default="/stereo_camera"/>
  <arg name="left_image_topic"        default="$(arg stereo_namespace)/left/image_rect_color" />
  <arg name="right_image_topic"       default="$(arg stereo_namespace)/right/image_rect" />     
  <arg name="left_camera_info_topic"  default="$(arg stereo_namespace)/left/camera_info" />
  <arg name="right_camera_info_topic" default="$(arg stereo_namespace)/right/camera_info" /> 
  
  <param name="use_action_for_goal" type="bool" value="true"/>
  <remap from="move_base"            to="/move_base"/>


  <!-- Already synchronized RGB-D related topic, with rtabmap_ros/rgbd_sync nodelet -->
  <arg name="rgbd_sync"               value="true"/>         <!-- pre-sync rgb_topic, depth_topic, camera_info_topic -->
  <arg name="approx_rgbd_sync"        value="true"/>          <!-- false=exact synchronization -->
  <arg name="subscribe_rgbd"          value="$(arg rgbd_sync)"/>
  <arg name="rgbd_topic"              value="rgbd_image" />
  <arg name="depth_scale"             value="1" />
  
  <arg name="compressed"              value="false"/>         <!-- If you want to subscribe to compressed image topics -->
  <arg name="rgb_image_transport"     value="compressed"/>    <!-- Common types: compressed, theora (see "rosrun image_transport list_transports") -->
  <arg name="depth_image_transport"   value="compressedDepth"/>  <!-- Depth compatible types: compressedDepth (see "rosrun image_transport list_transports") -->
   
  <arg name="subscribe_scan"          value="false"/>
  <arg name="scan_topic"              value="/scan"/>
  <arg name="subscribe_scan_cloud"    value="true"/>
  <arg name="scan_cloud_topic"        value="/scan_cloud"/>
  <arg name="scan_normal_k"           value="10"/>
   
  <arg name="visual_odometry"          value="false"/>          <!-- Launch rtabmap visual odometry node -->
  <arg name="icp_odometry"             value="true"/>         <!-- Launch rtabmap icp odometry node -->
  <arg name="odom_topic"               value="odom"/>          <!-- Odometry topic name -->
  <arg name="vo_frame_id"              value="$(arg odom_topic)"/> <!-- Visual/Icp odometry frame ID for TF -->
  <arg name="publish_tf_odom"          value="true"/>
  <arg name="odom_tf_angular_variance" value="0.0001"/>             <!-- If TF is used to get odometry, this is the default angular variance -->
  <arg name="odom_tf_linear_variance"  value="0.0001"/>             <!-- If TF is used to get odometry, this is the default linear variance -->
  <arg name="odom_args"                value=""/>              <!-- More arguments for odometry (overwrite same parameters in rtabmap_args) -->
  <arg name="odom_sensor_sync"         value="false"/>
  <arg name="odom_guess_frame_id"        value=""/>
  <arg name="odom_guess_min_translation" value="0"/>
  <arg name="odom_guess_min_rotation"    value="0"/> 
  <arg name="imu_topic"                value="/imu/data"/>          <!-- only used with VIO approaches -->
  <arg name="wait_imu_to_init"         value="false"/>
  
  <arg name="subscribe_user_data"      value="false"/>             <!-- user data synchronized subscription -->
  <arg name="user_data_topic"          value="/user_data"/>
  <arg name="user_data_async_topic"    value="/user_data_async" /> <!-- user data async subscription (rate should be lower than map update rate) -->
  
  <arg name="gps_topic"                value="/gps/fix" />         <!-- gps async subscription -->
  
  <arg name="tag_topic"                value="/tag_detections" />  <!-- apriltags async subscription -->
  <arg name="tag_linear_variance"      value="0.0001" />
  <arg name="tag_angular_variance"     value="9999" />             <!-- >=9999 means ignore rotation in optimization, when rotation estimation of the tag is not reliable -->
  
  <!-- These arguments should not be modified directly, see referred topics without "_relay" suffix above -->
  <arg if="$(arg compressed)"     name="rgb_topic_relay"           value="$(arg rgb_topic)_relay"/>
  <arg unless="$(arg compressed)" name="rgb_topic_relay"           value="$(arg rgb_topic)"/>
  <arg if="$(arg compressed)"     name="depth_topic_relay"         value="$(arg depth_topic)_relay"/>
  <arg unless="$(arg compressed)" name="depth_topic_relay"         value="$(arg depth_topic)"/>
  <arg if="$(arg compressed)"     name="left_image_topic_relay"    value="$(arg left_image_topic)_relay"/>
  <arg unless="$(arg compressed)" name="left_image_topic_relay"    value="$(arg left_image_topic)"/>
  <arg if="$(arg compressed)"     name="right_image_topic_relay"   value="$(arg right_image_topic)_relay"/>
  <arg unless="$(arg compressed)" name="right_image_topic_relay"   value="$(arg right_image_topic)"/>
  <arg if="$(arg rgbd_sync)"      name="rgbd_topic_relay"          value="$(arg rgbd_topic)"/>
  <arg unless="$(arg rgbd_sync)"  name="rgbd_topic_relay"          value="$(arg rgbd_topic)_relay"/>



  <!-- Nodes -->
  <group ns="$(arg namespace)">
     
    <!-- relays -->
    <group unless="$(arg stereo)">
      <group unless="$(arg subscribe_rgbd)">
        <node if="$(arg compressed)" name="republish_rgb" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg rgb_topic) raw out:=$(arg rgb_topic_relay)" />
        <node if="$(arg compressed)" name="republish_depth" type="republish" pkg="image_transport" args="$(arg depth_image_transport) in:=$(arg depth_topic) raw out:=$(arg depth_topic_relay)" />
      </group>
      <group if="$(arg rgbd_sync)">
        <node if="$(arg compressed)" name="republish_rgb" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg rgb_topic) raw out:=$(arg rgb_topic_relay)" />
        <node if="$(arg compressed)" name="republish_depth" type="republish" pkg="image_transport" args="$(arg depth_image_transport) in:=$(arg depth_topic) raw out:=$(arg depth_topic_relay)" />
        <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="$(arg output)">
          <remap from="rgb/image"       to="$(arg rgb_topic_relay)"/>
          <remap from="depth/image"     to="$(arg depth_topic_relay)"/>
          <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
          <remap from="rgbd_image"      to="$(arg rgbd_topic_relay)"/>
          <param name="approx_sync"     type="bool"   value="$(arg approx_rgbd_sync)"/>
          <param name="queue_size"      type="int"    value="$(arg queue_size)"/>
          <param name="depth_scale"     type="double" value="$(arg depth_scale)"/>
        </node>
      </group>
    </group>
    <group if="$(arg stereo)">
      <group unless="$(arg subscribe_rgbd)">
        <node if="$(arg compressed)" name="republish_left"  type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg left_image_topic) raw out:=$(arg left_image_topic_relay)" />
        <node if="$(arg compressed)" name="republish_right" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg right_image_topic) raw out:=$(arg right_image_topic_relay)" />
      </group>
      <group if="$(arg rgbd_sync)">
        <node if="$(arg compressed)" name="republish_left"  type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg left_image_topic) raw out:=$(arg left_image_topic_relay)" />
        <node if="$(arg compressed)" name="republish_right" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg right_image_topic) raw out:=$(arg right_image_topic_relay)" />
        <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/stereo_sync" output="$(arg output)">
          <remap from="left/image_rect"   to="$(arg left_image_topic_relay)"/>
          <remap from="right/image_rect"  to="$(arg right_image_topic_relay)"/>
          <remap from="left/camera_info"  to="$(arg left_camera_info_topic)"/>
          <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/>
          <remap from="rgbd_image"      to="$(arg rgbd_topic_relay)"/>
          <param name="approx_sync"     type="bool"   value="$(arg approx_rgbd_sync)"/>
          <param name="queue_size"      type="int"    value="$(arg queue_size)"/>
        </node>
      </group>
    </group>
    
    <group unless="$(arg rgbd_sync)">
       <group if="$(arg subscribe_rgbd)">
         <node name="republish_rgbd_image"  type="rgbd_relay" pkg="rtabmap_ros">
           <remap     if="$(arg compressed)" from="rgbd_image" to="$(arg rgbd_topic)/compressed"/>
           <remap     if="$(arg compressed)" from="$(arg rgbd_topic)/compressed_relay" to="$(arg rgbd_topic_relay)"/>
           <remap unless="$(arg compressed)" from="rgbd_image" to="$(arg rgbd_topic)"/>
           <param if="$(arg compressed)" name="uncompress" value="true"/>
         </node>
      </group>
    </group>

    <!-- Visual odometry -->
    <group unless="$(arg icp_odometry)">
      <group if="$(arg visual_odometry)">
      
        <!-- RGB-D Odometry -->
        <node unless="$(arg stereo)" pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)">
          <remap from="rgb/image"       to="$(arg rgb_topic_relay)"/>
          <remap from="depth/image"     to="$(arg depth_topic_relay)"/>
          <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
          <remap from="rgbd_image"      to="$(arg rgbd_topic_relay)"/>
          <remap from="odom"            to="$(arg odom_topic)"/>
      
          <param name="frame_id"                    type="string" value="$(arg frame_id)"/>
          <param name="odom_frame_id"               type="string" value="$(arg vo_frame_id)"/>
          <param name="publish_tf"                  type="bool"   value="$(arg publish_tf_odom)"/>
          <param name="ground_truth_frame_id"       type="string" value="$(arg ground_truth_frame_id)"/>
          <param name="ground_truth_base_frame_id"  type="string" value="$(arg ground_truth_base_frame_id)"/>
          <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
          <param name="wait_imu_to_init"            type="bool"   value="$(arg wait_imu_to_init)"/>
          <param name="approx_sync"                 type="bool"   value="$(arg approx_sync)"/>
          <param name="config_path"                 type="string" value="$(arg cfg)"/>
          <param name="queue_size"                  type="int"    value="$(arg queue_size)"/>
          <param name="subscribe_rgbd"              type="bool"   value="$(arg subscribe_rgbd)"/>
          <param name="guess_frame_id"              type="string" value="$(arg odom_guess_frame_id)"/>
          <param name="guess_min_translation"       type="double" value="$(arg odom_guess_min_translation)"/>
          <param name="guess_min_rotation"          type="double" value="$(arg odom_guess_min_rotation)"/>
        </node>

        <!-- Stereo Odometry -->
        <node if="$(arg stereo)" pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)">
          <remap from="left/image_rect"        to="$(arg left_image_topic_relay)"/>
          <remap from="right/image_rect"       to="$(arg right_image_topic_relay)"/>
          <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
          <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>
          <remap from="rgbd_image"             to="$(arg rgbd_topic_relay)"/>
          <remap from="odom"                   to="$(arg odom_topic)"/>
          <remap from="imu"                    to="$(arg imu_topic)"/>
      
          <param name="frame_id"                    type="string" value="$(arg frame_id)"/>
          <param name="odom_frame_id"               type="string" value="$(arg vo_frame_id)"/>
          <param name="publish_tf"                  type="bool"   value="$(arg publish_tf_odom)"/>
          <param name="ground_truth_frame_id"       type="string" value="$(arg ground_truth_frame_id)"/>
          <param name="ground_truth_base_frame_id"  type="string" value="$(arg ground_truth_base_frame_id)"/>
          <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
          <param name="wait_imu_to_init"            type="bool"   value="$(arg wait_imu_to_init)"/>
          <param name="approx_sync"                 type="bool"   value="$(arg approx_sync)"/>
          <param name="config_path"                 type="string" value="$(arg cfg)"/>
          <param name="queue_size"                  type="int"    value="$(arg queue_size)"/>
          <param name="subscribe_rgbd"              type="bool"   value="$(arg subscribe_rgbd)"/>
          <param name="guess_frame_id"              type="string" value="$(arg odom_guess_frame_id)"/>
          <param name="guess_min_translation"       type="double" value="$(arg odom_guess_min_translation)"/>
          <param name="guess_min_rotation"          type="double" value="$(arg odom_guess_min_rotation)"/>
        </node>
      </group>
    </group>
    
    <!-- ICP Odometry -->
    <node if="$(arg icp_odometry)" pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)">
      <remap from="scan"                   to="$(arg scan_topic)"/>
      <remap from="scan_cloud"             to="$(arg scan_cloud_topic)"/>
      <remap from="odom"                   to="$(arg odom_topic)"/>
      
      <param name="frame_id"                    type="string" value="$(arg frame_id)"/>
      <param name="odom_frame_id"               type="string" value="$(arg vo_frame_id)"/>
      <param name="publish_tf"                  type="bool"   value="$(arg publish_tf_odom)"/>
      <param name="ground_truth_frame_id"       type="string" value="$(arg ground_truth_frame_id)"/>
      <param name="ground_truth_base_frame_id"  type="string" value="$(arg ground_truth_base_frame_id)"/>
      <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
      <param name="wait_imu_to_init"            type="bool"   value="$(arg wait_imu_to_init)"/>
      <param name="config_path"                 type="string" value="$(arg cfg)"/>
      <param name="queue_size"                  type="int"    value="$(arg queue_size)"/>
      <param name="guess_frame_id"              type="string" value="$(arg odom_guess_frame_id)"/>
      <param name="guess_min_translation"       type="double" value="$(arg odom_guess_min_translation)"/>
      <param name="guess_min_rotation"          type="double" value="$(arg odom_guess_min_rotation)"/>
        <!-- ICP parameters -->
      <param name="Icp/PointToPlane"        type="string" value="true"/>
      <param name="Icp/Iterations"          type="string" value="10"/> 
      <param name="Icp/VoxelSize"           type="string" value="0.3"/>   <!-- 0.2-->
      <param name="Icp/DownsamplingStep"    type="string" value="1"/> <!-- cannot be increased with ring-like lidar -->
      <param name="Icp/Epsilon"             type="string" value="0.001"/>
      <param name="Icp/PointToPlaneK"       type="string" value="20"/>
      <param name="Icp/PointToPlaneRadius"  type="string" value="0"/>
      <param name="Icp/MaxTranslation"      type="string" value="2"/>
      <param name="Icp/MaxCorrespondenceDistance" type="string" value="1"/>
      <param name="Icp/PM"                  type="string" value="true"/> 
      <param name="Icp/PMOutlierRatio"      type="string" value="0.1"/>
      <param name="Icp/CorrespondenceRatio" type="string" value="0.01"/>  
     <!-- <param name="Icp/RangeMax"            type="string" value="20.0"/> -->

      <!-- Odom parameters -->       
      <param name="Odom/ScanKeyFrameThr"       type="string" value="0.95"/>
      <param name="Odom/Strategy"              type="string" value="0"/>


      <param name="Reg/Force3DoF"              type="bool" value="true"/>
      <!-- <param name="OdomF2M/ScanSubtractRadius" type="string" value="0.2"/> -->
      <!-- <param name="OdomF2M/ScanMaxSize"        type="string" value="15000"/> -->     
    </node>
  
    <!-- Visual SLAM (robot side) -->
    <!-- args: "delete_db_on_start" and "udebug" -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="$(arg output)" args="$(arg rtabmap_args)" launch-prefix="$(arg launch_prefix)">
      <param     if="$(arg stereo)" name="subscribe_depth"  type="bool" value="false"/>
      <param unless="$(arg stereo)" name="subscribe_depth"  type="bool" value="true"/>
      <param name="subscribe_rgbd"       type="bool"   value="$(arg subscribe_rgbd)"/>
      <param name="subscribe_stereo"     type="bool"   value="$(arg stereo)"/>
      <param name="subscribe_scan"       type="bool"   value="$(arg subscribe_scan)"/>
      <param name="subscribe_scan_cloud" type="bool"   value="$(arg subscribe_scan_cloud)"/>
      <param name="subscribe_user_data"  type="bool"   value="$(arg subscribe_user_data)"/>
      <param if="$(arg visual_odometry)" name="subscribe_odom_info" type="bool" value="true"/>
      <param if="$(arg icp_odometry)"    name="subscribe_odom_info" type="bool" value="true"/>
      <param name="frame_id"             type="string" value="$(arg frame_id)"/>
      <param name="map_frame_id"         type="string" value="$(arg map_frame_id)"/>
      <param name="odom_frame_id"        type="string" value="$(arg odom_frame_id)"/>
      <param name="publish_tf"           type="bool"   value="$(arg publish_tf_map)"/>
      <param name="ground_truth_frame_id"       type="string" value="$(arg ground_truth_frame_id)"/>
      <param name="ground_truth_base_frame_id"  type="string" value="$(arg ground_truth_base_frame_id)"/>
      <param name="odom_tf_angular_variance" type="double" value="$(arg odom_tf_angular_variance)"/>
      <param name="odom_tf_linear_variance"  type="double" value="$(arg odom_tf_linear_variance)"/>
      <param name="odom_sensor_sync"         type="bool"   value="$(arg odom_sensor_sync)"/>
      <param name="wait_for_transform_duration"  type="double"   value="$(arg wait_for_transform)"/>
      <param name="database_path"        type="string" value="$(arg database_path)"/>
      <param name="approx_sync"          type="bool"   value="$(arg approx_sync)"/>
      <param name="config_path"          type="string" value="$(arg cfg)"/>
      <param name="queue_size"           type="int" value="$(arg queue_size)"/>
      <param name="scan_normal_k"        type="int" value="$(arg scan_normal_k)"/>
      <param name="landmark_linear_variance"   type="double" value="$(arg tag_linear_variance)"/>
      <param name="landmark_angular_variance"  type="double" value="$(arg tag_angular_variance)"/>      

      
      <param name="Reg/Strategy"                   type="string" value="1"/> <!--1 ICP registration (vorher) / 2 ICP + Visual-->
      <param name="RGBD/OptimizeMaxError"          type="double" value="100.0"  />
      <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/>
      <param name="RGBD/ProximityBySpace"          type="bool" value="true"/>
      <param name="RGBD/GoalReachedRadius"         type="double" value="2.0"/>

      <param name="Optimizer/GravitySigma"          type="double" value="0.3"  /> 

      <param name="use_action_for_goal" type="bool" value="true"/> 
      <remap from="move_base" to="/planner/move_base"/>


      <param name="Reg/Force3DoF"              type="bool" value="true"/>
      <param name="Optimizer/Slam2D"           type="bool" value="true" />

      <param name="Grid/CellSize"                  type="double" value="0.25"/>
      <param name="Grid/ClusterRadius"             type="double" value="1.0"/>
      <param name="Grid/FromDepth"                 type="bool" value="false"/>
      <param name="Grid/MaxGroundAngle"            type="int" value="50"/>
      <param name="Grid/NoiseFilteringRadius"      type="double" value="0.5"/>
      <param name="Grid/RangeMax"                  type="double" value="10.0"/>
 

      <!-- RTAB-Map's parameters -->
      <!--<param name="RGBD/NeighborLinkRefining"      type="string" value="true"/> -->  <!-- set true to refine odometry with lidar -->
      <!-- <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="20"/> -->
        
  
      <remap from="rgb/image"       to="$(arg rgb_topic_relay)"/>
      <remap from="depth/image"     to="$(arg depth_topic_relay)"/>
      <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
      
      <remap from="rgbd_image"      to="$(arg rgbd_topic_relay)"/>
	
      <remap from="left/image_rect"        to="$(arg left_image_topic_relay)"/>
      <remap from="right/image_rect"       to="$(arg right_image_topic_relay)"/>
      <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
      <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>
      
      <remap from="scan"                   to="$(arg scan_topic)"/>
      <remap from="scan_cloud"             to="$(arg scan_cloud_topic)"/>
      <remap from="user_data"              to="$(arg user_data_topic)"/>
      <remap from="user_data_async"        to="$(arg user_data_async_topic)"/>
      <remap from="gps/fix"                to="$(arg gps_topic)"/>
      <remap from="tag_detections"         to="$(arg tag_topic)"/>
      <remap from="odom"                   to="$(arg odom_topic)"/>
      <remap from="imu"                    to="$(arg imu_topic)"/>
      
      <!-- localization mode -->
      <param     if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
      <param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
      <param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
    </node>
  
    <!-- Visualisation RTAB-Map -->
    <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(arg gui_cfg)" output="$(arg output)" launch-prefix="$(arg launch_prefix)">
      <param     if="$(arg stereo)" name="subscribe_depth"  type="bool" value="false"/>
      <param unless="$(arg stereo)" name="subscribe_depth"  type="bool" value="true"/>
      <param name="subscribe_rgbd"       type="bool"   value="$(arg subscribe_rgbd)"/>
      <param name="subscribe_stereo"     type="bool"   value="$(arg stereo)"/>
      <param name="subscribe_scan"       type="bool"   value="$(arg subscribe_scan)"/>
      <param name="subscribe_scan_cloud" type="bool"   value="$(arg subscribe_scan_cloud)"/>
      <param if="$(arg visual_odometry)" name="subscribe_odom_info" type="bool" value="true"/>
      <param if="$(arg icp_odometry)"    name="subscribe_odom_info" type="bool" value="true"/>
      <param name="frame_id"             type="string" value="$(arg frame_id)"/>
      <param name="odom_frame_id"        type="string" value="$(arg odom_frame_id)"/>
      <param name="wait_for_transform_duration" type="double"   value="$(arg wait_for_transform)"/>
      <param name="queue_size"           type="int"    value="$(arg queue_size)"/>
      <param name="approx_sync"          type="bool"   value="$(arg approx_sync)"/>
    
      <remap from="rgb/image"       to="$(arg rgb_topic_relay)"/>
      <remap from="depth/image"     to="$(arg depth_topic_relay)"/>
      <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
      
      <remap from="rgbd_image"      to="$(arg rgbd_topic_relay)"/>
      
      <remap from="left/image_rect"        to="$(arg left_image_topic_relay)"/>
      <remap from="right/image_rect"       to="$(arg right_image_topic_relay)"/>
      <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
      <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>
      
      <remap from="scan"                   to="$(arg scan_topic)"/>
      <remap from="scan_cloud"             to="$(arg scan_cloud_topic)"/>
      <remap from="odom"                   to="$(arg odom_topic)"/>
    </node>
  
  </group>
  
  <!-- Visualization RVIZ -->
  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(arg rviz_cfg)"/>
  <node if="$(arg rviz)" pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb" output="$(arg output)">
    <remap if="$(arg stereo)" from="left/image"        to="$(arg left_image_topic_relay)"/>
    <remap if="$(arg stereo)" from="right/image"       to="$(arg right_image_topic_relay)"/>
    <remap if="$(arg stereo)" from="left/camera_info"  to="$(arg left_camera_info_topic)"/>
    <remap if="$(arg stereo)" from="right/camera_info" to="$(arg right_camera_info_topic)"/>
    <remap unless="$(arg subscribe_rgbd)" from="rgb/image"         to="$(arg rgb_topic_relay)"/>
    <remap unless="$(arg subscribe_rgbd)" from="depth/image"       to="$(arg depth_topic_relay)"/>
    <remap unless="$(arg subscribe_rgbd)" from="rgb/camera_info"   to="$(arg camera_info_topic)"/>
    <remap from="rgbd_image"        to="$(arg rgbd_topic_relay)"/>
    <remap from="cloud"             to="voxel_cloud" />

    <param name="decimation"  type="double" value="4"/>
    <param name="voxel_size"  type="double" value="0.0"/>
    <param name="approx_sync" type="bool"   value="$(arg approx_sync)"/>
  </node>

</launch>
move base launch file:
<launch>
  
    <arg name="use_sim_time"            value="true"/>  
    <param if="$(arg use_sim_time)" name="use_sim_time" value="true"/>  
  
   <group ns="planner">
      <remap from="scan_cloud" to="/planner_cloud"/>
      <remap from="map" to="/rtabmap/grid_map"/>
     <!-- <remap from="move_base_simple/goal" to="/planner_goal"/> -->


   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="/home/launch/navigation/costmap_common_params.yaml" command="load" ns="global_costmap" /> 
    <rosparam file="/home/launch/navigation/costmap_common_params.yaml" command="load" ns="local_costmap" />
    <rosparam file="/home/launch/navigation/local_costmap_params.yaml" command="load" />
    <rosparam file="/home/launch/navigation/global_costmap_params.yaml" command="load" /> 
    <rosparam file="/home/launch/navigation/base_local_planner_params.yaml" command="load" />
 </node>

</group>

</launch> 
Yaml files:
obstacle_range: 10.0
raytrace_range: 15.0
max_obstacle_height: 999.0
min_obstacle_height: -999.9
#footprint: [[x0, y0], [x1, y1], ... [xn, yn]]
#robot_radius: ir_of_robot
inflation_radius: 0.55

observation_sources: point_cloud_sensor         # list of sensors
point_cloud_sensor: {sensor_frame: laser, data_type: PointCloud2, topic: /scan_cloud, marking: true, clearing: true}

#laser_scan_sensor: {sensor_frame: frame_name, data_type: LaserScan, topic: topic_name, marking: true, clearing: true}





local_costmap:
  global_frame: odom
  robot_base_frame: base_link
  update_frequency: 5.0
  publish_frequency: 2.0
  static_map: false
  rolling_window: true        #local_costmap stays centered during navigation
  width: 20
  height: 20
  resolution: 0.1


global_costmap:
  global_frame: map
  robot_base_frame: base_link
  update_frequency: 5.0
  static_map: true



TrajectoryPlannerROS:
  max_vel_x: 0.45                 
  min_vel_x: 0.1
  max_vel_theta: 1.0
  min_in_place_vel_theta: 0.4

  acc_lim_theta: 3.2
  acc_lim_x: 2.5
  acc_lim_y: 2.5

  xy_goal_tolerance: 4.0
  pdist_scale: 1.8


  holonomic_robot: true
Many thanks in advance!!
Reply | Threaded
Open this post in threaded view
|

Re: Question regarding path planning

matlabbe
Administrator
You should look at the global path computed by move_base. The one from rtabmap is taking only the nodes in the graph as waypoints, but rtabmap should send those waypoints to move_base, which will compute a smooth path based on the global costmap.

cheers,
Mathieu