ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

ROS noetic navigation without using a map

asked 2021-07-22 02:00:42 -0500

yhymason gravatar image

Hi there, I am planning to use a loco-motion robot mounted with RGB-D camera to navigate through indoor space. I wonder how I can make a ROS planner work without a pre-defined map of the space.

edit retag flag offensive close merge delete

Comments

You can configure the navigation stack global planner and global costmap to use odom instead of map as global frame, provided you have a painted floor plan. You could also use depthimage_to_laserscan for SLAM so you get a map. Or you can use rtabmap for SLAM.

Humpelstilzchen gravatar image Humpelstilzchen  ( 2021-07-23 16:01:57 -0500 )edit

can you please give me an example launch file of how to set this up? is there a similar turtle launch file I can refer to? I am so far not very sure about how each component should work with each other

yhymason gravatar image yhymason  ( 2021-07-25 01:43:01 -0500 )edit

Which version? 1) odom as global 2) depthimage_to_laserscan or 3) rtabmap?

Humpelstilzchen gravatar image Humpelstilzchen  ( 2021-07-25 02:07:47 -0500 )edit

I am on ROS noetic.

yhymason gravatar image yhymason  ( 2021-07-25 02:10:41 -0500 )edit

I meant: Which version do you want the example launch file for?

Humpelstilzchen gravatar image Humpelstilzchen  ( 2021-07-25 02:20:15 -0500 )edit

Oh I'd like to see an example of using odom as global so that I can run SLAM while planning.

yhymason gravatar image yhymason  ( 2021-07-25 02:50:24 -0500 )edit

Aah sorry, I misunderstood your question, so you are already creating the map with SLAM (e.g. gmapping) and have an area with unknown obstacles but still have a x/y coordinate for your robot to go to, is that correct? If not please rewrite your original question and add more details, e.g. node tree, launch files etc.

The global_planner has a parameter allow_unknown which might resolve your problem. But I have never used that it and have no experience with it.

Humpelstilzchen gravatar image Humpelstilzchen  ( 2021-07-25 03:04:00 -0500 )edit

You didn't misunderstand my question, I am not creating a map at all. All I want is to provide my robot with an RGB-D camera & a given goal location & its location relative to the goal. I want to let it navigate through an unknown space. So in short, using a SLAM package or not, I am not gonna create a map for the robot to use. I just need a ROS planner or a way to make this work.

yhymason gravatar image yhymason  ( 2021-07-25 03:09:17 -0500 )edit

3 Answers

Sort by » oldest newest most voted
0

answered 2021-07-27 07:09:04 -0500

Humpelstilzchen gravatar image

I still don't know if I understood your question correctly, but here is how to use navigation & slam together for turtlebot 3 simulation:

  1. Start the simulation as documented

    export TURTLEBOT3_MODEL=waffle_pi roslaunch turtlebot3_gazebo turtlebot3_house.launch

  2. Start SLAM with gmapping as [documented] (https://emanual.robotis.com/docs/en/p...): export TURTLEBOT3_MODEL=burger roslaunch turtlebot3_slam turtlebot3_slam.launch slam_methods:=gmapping

  3. Start the navigation stack: The documentation says to launch turtlebot3_navigation.launch but this requires a map parameter for the map_server and amcl. But we already have the map from SLAM/gmapping, so we copy turtlebot3_navigation.launch and remove the lines for amcl and map_server:

turtlebot3_navigation_nomap.launch:

<launch>
  <!-- Arguments -->
  <arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
  <arg name="open_rviz" default="true"/>
  <arg name="move_forward_only" default="false"/>

  <!-- Turtlebot3 -->
  <include file="$(find turtlebot3_bringup)/launch/turtlebot3_remote.launch">
    <arg name="model" value="$(arg model)" />
  </include>

  <!-- move_base -->
  <include file="$(find turtlebot3_navigation)/launch/move_base.launch">
    <arg name="model" value="$(arg model)" />
    <arg name="move_forward_only" value="$(arg move_forward_only)"/>
  </include>

  <!-- rviz -->
  <group if="$(arg open_rviz)"> 
    <node pkg="rviz" type="rviz" name="rviz" required="true"
          args="-d $(find turtlebot3_navigation)/rviz/turtlebot3_navigation.rviz"/>
  </group>
</launch>

and launch it:

export TURTLEBOT3_MODEL=burger
roslaunch turtlebot3_navigation turtlebot3_navigation_nomap.launch

Finally we can start rviz and can now set a goal position for the navigation stack.

edit flag offensive delete link more

Comments

amazing! I will try this!

yhymason gravatar image yhymason  ( 2021-07-28 03:14:04 -0500 )edit
0

answered 2021-07-25 17:14:58 -0500

yhymason gravatar image

updated 2021-07-25 17:19:08 -0500

Below is my main launch file, it launches multiple nodes to convert sensors readings published from the simulation engine I am using.

<?xml version="1.0"?>
<launch>

    <node pkg="ros_x_habitat" type="depth_ros.py" name="depth_ros" >
        <remap from="depth" to="habitat/depth"/>
    </node>

    <node pkg="ros_x_habitat" type="rgb_ros.py" name="rgb_ros">
        <remap from="rgb" to="habitat/rgb"/>
    </node>
    <node pkg="image_view" type="image_view" name="image_view">
        <remap from="image" to="ros_img_rgb"/>
    </node>
    <node pkg="rqt_graph" type="rqt_graph" name="rqt_graph"/>
    <node pkg="rqt_tf_tree" type="rqt_tf_tree" name="rqt_tf_tree"/>

    <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan">
        <remap from="image" to="ros_img_depth"/>
        <remap from="camera_info" to="camera_info_topic"/>
        <param name="output_frame_id" value="laser"/>
        <param name="scan_time" value="0.025" />
    </node>

    <node pkg="laser_scan_matcher" type="laser_scan_matcher_node" name="laser_scan_matcher_node" output="screen">
        <param name="max_iterations" value="10"/>
        <param name="fixed_frame" value="odom"/>
        <param name="base_frame" value="base_frame"/>
    </node>

    <node pkg="tf" type="static_transform_publisher" name="base_frame_to_laser" args="0.0 0.0 0.0 0.0 0.0 0.0 /base_frame /laser 50" />

</launch>

Here is the move_base launch file I am using, I guess we need to get rid of AMCL and map stuff since we don't want to use a map.

<?xml version="1.0"?>
<launch>

   <arg name="map_path" default="$(find ros_x_habitat)/maps/mymap.yaml"/>

   <master auto="start"/>

   <!-- Run the map server -->
   <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_path)"/>


   <!--- Run AMCL -->
   <node pkg="amcl" type="amcl" name="amcl">
      <!-- Publish scans from best pose at a max of 10 Hz -->
      <param name="odom_model_type" value="diff"/>
      <param name="odom_alpha5" value="0.2"/>
      <param name="transform_tolerance" value="1" />
      <param name="gui_publish_rate" value="10.0"/>
      <param name="laser_max_beams" value="30"/>
      <param name="min_particles" value="500"/>
      <param name="max_particles" value="5000"/>
      <param name="kld_err" value="0.05"/>
      <param name="kld_z" value="0.99"/>
      <param name="odom_alpha1" value="0.2"/>
      <param name="odom_alpha2" value="0.2"/>
      <!-- translation std dev, m -->
      <param name="odom_alpha3" value="0.2"/>
      <param name="odom_alpha4" value="0.2"/>
      <param name="laser_z_hit" value="0.5"/>
      <param name="laser_z_short" value="0.05"/>
      <param name="laser_z_max" value="0.05"/>
      <param name="laser_z_rand" value="0.5"/>
      <param name="laser_sigma_hit" value="0.2"/>
      <param name="laser_lambda_short" value="0.1"/>
      <param name="laser_lambda_short" value="0.1"/>
      <param name="laser_model_type" value="likelihood_field"/>
      <!-- <param name="laser_model_type" value="beam"/> -->
      <param name="laser_likelihood_max_dist" value="2.0"/>
      <param name="update_min_d" value="0.2"/>
      <param name="update_min_a" value="0.5"/>
      <param name="odom_frame_id" value="odom"/>
      <param name="resample_interval" value="1"/>
      <param name="transform_tolerance" value="1"/>
      <param name="recovery_alpha_slow" value="0.0"/>
      <param name="recovery_alpha_fast" value="0.0"/>
      <param name="base_frame_id " value="base_frame"/>
   </node>

   <node pkg="move_base ...
(more)
edit flag offensive delete link more

Comments

The planner I am using is TrajectoryPlannerROS: max_vel_x: 1 min_vel_x: -0.1 max_vel_theta: 5 min_in_place_vel_theta: -3

acc_lim_theta: 1 acc_lim_x: 2.5 acc_lim_y: 2.5

holonomic_robot: false meter_scoring: true controller_frequency: 10.0

yhymason gravatar image yhymason  ( 2021-07-25 17:20:20 -0500 )edit

cost map common params: obstacle_range: 2 raytrace_range: 2

robot_radius: 0.1 inflation_radius: 0.5

observation_sources: laser_scan_sensor

laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}

yhymason gravatar image yhymason  ( 2021-07-25 17:23:58 -0500 )edit

global_costmap: global_frame: map robot_base_frame: base_frame update_frequency: 10.0 static_map: true

yhymason gravatar image yhymason  ( 2021-07-25 17:24:22 -0500 )edit

local_costmap: global_frame: odom robot_base_frame: base_frame transform_tolerance: 0.3 update_frequency: 5.0 publish_frequency: 3.0 static_map: false rolling_window: true width: 60.0 height: 60.0 resolution: 0.05

yhymason gravatar image yhymason  ( 2021-07-25 17:24:40 -0500 )edit

It would have been a better style to edit your question and add the configuration there. Also a node graph please (Output of rqt_graph)

Humpelstilzchen gravatar image Humpelstilzchen  ( 2021-07-26 00:59:19 -0500 )edit

I don't have the output of rqt_graph atm, since the simulation engine is not working properly due to a recent upgrade, I am still working on refactoring the code. but everything with the launch files should work.

yhymason gravatar image yhymason  ( 2021-07-26 01:16:05 -0500 )edit

ok, then I recommend to use the turtlebot 3 simulation as example for this question, ok?

Humpelstilzchen gravatar image Humpelstilzchen  ( 2021-07-26 06:17:23 -0500 )edit

it'd be great if you can teach me how to make turtlebot3 navigate without using a static map. so that I can replicate the modifications on my own work later.

yhymason gravatar image yhymason  ( 2021-07-26 14:49:31 -0500 )edit
0

answered 2021-07-22 07:47:33 -0500

You can simply use a completely empty map and trick the system so that it believes you have provided a map. I did this in the past and it worked as expected, though I suggest you at least enable a local map so robots doesn't crash around.

edit flag offensive delete link more

Comments

What is the advantage of using an empty map over just not using the map frame?

Humpelstilzchen gravatar image Humpelstilzchen  ( 2021-07-23 16:03:42 -0500 )edit

If you don’t have a map frame, then in which global frame you are going to represent navigation goals ?

Fetullah Atas gravatar image Fetullah Atas  ( 2021-08-02 16:29:45 -0500 )edit

Let’s say you use Odom frame. That works too, in ros based navigation frameworks that I know, it’s common to have a global and local map, it’s easier just provide an empty map rather than playing with config files and figure a way to do navigation without a prior map. This is my personal opinion

Fetullah Atas gravatar image Fetullah Atas  ( 2021-08-02 16:35:27 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-07-22 02:00:42 -0500

Seen: 938 times

Last updated: Jul 27 '21