/map not connecting to tf links for loading multiple robots in rviz
I am trying to load two robots in Gazebo and visualize them in Rviz to eventually do a leader-follower application. I believe I have the robots initialized in Gazebo correctly and mostly in Rviz, but am having trouble getting the /map topic to link up to either of the robots. I can teleop with the robots separately in Gazebo using their respective namespaces. I am simulating using a turtlebot3 wafflepi. I'm thinking the problem has something to do with remapping from "map" to "/map" or in how my amcl node is called under the tfprefixes for my two robots.
From running rosrun rqt_graph rqt_graph
I can see that both of my two robots are initialized with their respective connections to /tf and /gazebo. (would upload output image but not enough user points).
From running rosrun tf view_frames
I can see that both robots have root parents of "bot1tf/odom" and "bot2tf/odom" where "botXtf" is the tfprefix. The children connections seem to match output from running a single robot in Gazebo/Rviz. The only thing different seems to be that "/map" is the parent for "/odom" for the single robot, while there is no "/map" parent for the two robots.
Upon loading Rviz I see a green check next to URDF making me thing Rviz is reading in the model correctly, though all other tf topics have errors. When I manually enter either tfprefix in the "TF Prefix" field in Rviz under "RobotModel" I see errors saying "No transform from [tfprefix/basefootprint] to [map]" and so on for the other tf topics (basefootprint, baselink, basescan, cameralink, camerargbframe, camerargbopticalframe, casterbackleftlink, casterbackrightlink, imulink, wheelleftlink, wheelright_link).
Running rosnode list
results in the following:
/bot1/amcl
/bot1/move_base
/bot1/robot_state_publisher
/bot2/amcl
/bot2/move_base
/bot2/robot_state_publisher
/gazebo
/gazebo_gui
/map_server
/rosout
/rviz
Running rostopic list
results in the following:
/bot1/amcl_pose
/bot1/camera/parameter_descriptions
/bot1/camera/parameter_updates
/bot1/camera/rgb/camera_info
/bot1/camera/rgb/image_raw
/bot1/camera/rgb/image_raw/compressed
/bot1/camera/rgb/image_raw/compressed/parameter_descriptions
/bot1/camera/rgb/image_raw/compressed/parameter_updates
/bot1/camera/rgb/image_raw/compressedDepth
/bot1/camera/rgb/image_raw/compressedDepth/parameter_descriptions
/bot1/camera/rgb/image_raw/compressedDepth/parameter_updates
/bot1/camera/rgb/image_raw/theora
/bot1/camera/rgb/image_raw/theora/parameter_descriptions
/bot1/camera/rgb/image_raw/theora/parameter_updates
/bot1/cmd_vel
/bot1/imu
/bot1/initialpose
/bot1/joint_states
/bot1/move_base/current_goal
/bot1/move_base/goal
/bot1/move_base_simple/goal
/bot1/odom
/bot1/particlecloud
/bot1/scan
/bot2/amcl_pose
/bot2/camera/parameter_descriptions
/bot2/camera/parameter_updates
/bot2/camera/rgb/camera_info
/bot2/camera/rgb/image_raw
/bot2/camera/rgb/image_raw/compressed
/bot2/camera/rgb/image_raw/compressed/parameter_descriptions
/bot2/camera/rgb/image_raw/compressed/parameter_updates
/bot2/camera/rgb/image_raw/compressedDepth
/bot2/camera/rgb/image_raw/compressedDepth/parameter_descriptions /bot2/camera/rgb/image_raw/compressedDepth/parameter_updates
/bot2/camera/rgb/image_raw/theora
/bot2/camera/rgb/image_raw/theora/parameter_descriptions
/bot2/camera/rgb/image_raw/theora/parameter_updates
/bot2/cmd_vel
/bot2/imu
/bot2/initialpose
/bot2/joint_states
/bot2/move_base/current_goal
/bot2/move_base/goal
/bot2/move_base_simple/goal
/bot2/odom
/bot2/particlecloud
/bot2/scan
/clock
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/initialpose
/map
/map_metadata
/map_updates
/move_base/DWAPlannerROS/global_plan
/move_base/DWAPlannerROS/local_plan
/move_base/NavfnROS/plan
/move_base/global_costmap/costmap
/move_base/global_costmap/costmap_updates
/move_base/local_costmap/costmap
/move_base/local_costmap/costmap_updates
/move_base/local_costmap/footprint
/move_base_simple/goal
/particlecloud
/rosout
/rosout_agg
/scan
/tf
/tf_static
Investigating the /map topic by running rostopic info /map
shows:
Type: nav_msgs/OccupancyGrid
Publishers:
* /map_server (http://alex-UbuntuROS:40709/)
Subscribers:
* /rviz (http://alex-UbuntuROS:35671/)
When I loaded a single robot for navigation into Rviz I saw that /move_base was also subscribed to /map, which is why I think there is an issue with /map and/or node connections to it.
The error output I get from ROS is: (repeatedly printed in yellow)
[ WARN] [1561024615.579003098, 3390.937000000]: 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: source_frame base_footprint does not exist.. canTransform returned after 0.1 timeout was 0.1.
The files I'm using are as follows:
tutorialcustomworld_2bots.launch (load world and two robots into Gazebo)
<launch>
<!-- make world -->
<arg name="custom_world" default="plaza" />
<include file="$(find gazebo_ros)/launch/empty_world.launch" >
<arg name="world_name" value="$(find nus_bot)/worlds/$(arg custom_world).world"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
<!-- make robots -->
<include file="$(find nus_bot)/launch/tutorial_robots.launch" />
</launch>
tutorial_robots.launch (call launch file to initialize two robots)
<launch>
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro" />
<!-- bot1 -->
<group ns="bot1">
<param name="tf_prefix" value="bot1_tf" />
<include file="$(find nus_bot)/launch/tutorial_one_robot.launch" >
<arg name="init_pose" value="-x 0.0 -y 0.0 -z 0.0" />
<arg name="robot_name" value="Bot1" />
</include>
</group>
<!-- bot2 -->
<group ns="bot2">
<param name="tf_prefix" value="bot2_tf" />
<include file="$(find nus_bot)/launch/tutorial_one_robot.launch" >
<arg name="init_pose" value="-x 0.5 -y 0.5 -z 0.0" />
<arg name="robot_name" value="Bot2" />
</include>
</group>
</launch>
tutorialonerobot.launch (create a single robot, supposed to be called twice under different namespaces)
<launch>
<arg name="robot_name"/>
<arg name="init_pose"/>
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-urdf $(arg init_pose) -param /robot_description -model $(arg robot_name)" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" />
</launch>
tutorialnavigation2bots.launch (launch robots from Gazebo simulation to Rviz)
<launch>
<!-- Arguments -->
<arg name="map_file" default="plaza_map"/>
<arg name="open_rviz" default="true"/>
<!-- Map server -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find nus_bot)/maps/$(arg map_file).yaml" >
<param name="frame_id" value="/map" />
</node>
<!-- bot1 -->
<group ns="bot1">
<param name="tf_prefix" value="bot1_tf" />
<!-- AMCL node -->
<include file="$(find nus_bot)/launch/amcl.launch" />
<!-- move_base -->
<include file="$(find nus_bot)/launch/tutorial_move_base.launch" />
</group>
<!-- bot2 -->
<group ns="bot2">
<param name="tf_prefix" value="bot2_tf" />
<!-- AMCL node -->
<include file="$(find nus_bot)/launch/amcl.launch" />
<!-- move_base -->
<include file="$(find nus_bot)/launch/tutorial_move_base.launch" />
</group>
<!-- rviz -->
<group if="$(arg open_rviz)">
<node pkg="rviz" type="rviz" name="rviz" required="true"
args="-d $(find nus_bot)/rviz/turtlebot3_navigation.rviz">
<remap from="map" to="/map" />
</node>
</group>
</launch>
tutorialmovebase.launch (launch movebase for a robot, same as "normal" movebase but includes remapping from "map" to "/map")
<launch>
<!-- Arguments -->
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<arg name="move_forward_only" default="false"/>
<!-- move_base node -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
<rosparam file="$(find turtlebot3_navigation)/param/costmap_common_params_$(arg model).yaml" command="load" ns="global_costmap" />
<rosparam file="$(find turtlebot3_navigation)/param/costmap_common_params_$(arg model).yaml" command="load" ns="local_costmap" />
<rosparam file="$(find turtlebot3_navigation)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find turtlebot3_navigation)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find turtlebot3_navigation)/param/move_base_params.yaml" command="load" />
<rosparam file="$(find turtlebot3_navigation)/param/dwa_local_planner_params_$(arg model).yaml" command="load" />
<param name="DWAPlannerROS/min_vel_x" value="0.0" if="$(arg move_forward_only)" />
<remap from="map" to="/map" />
</node>
</launch>
amcl.launch (launch amcl.launch for robot, same as "normal" amcl.launch but includes remapping from "map" to "/map")
<launch>
<!-- Arguments -->
<arg name="scan_topic" default="scan"/>
<arg name="initial_pose_x" default="0.0"/>
<arg name="initial_pose_y" default="0.0"/>
<arg name="initial_pose_a" default="0.0"/>
<!-- AMCL -->
<node pkg="amcl" type="amcl" name="amcl">
<param name="min_particles" value="500"/>
<param name="max_particles" value="3000"/>
<param name="kld_err" value="0.02"/>
<param name="update_min_d" value="0.20"/>
<param name="update_min_a" value="0.20"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.5"/>
<param name="recovery_alpha_slow" value="0.00"/>
<param name="recovery_alpha_fast" value="0.00"/>
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
<param name="gui_publish_rate" value="50.0"/>
<remap from="scan" to="$(arg scan_topic)"/>
<param name="laser_max_range" value="3.5"/>
<param name="laser_max_beams" value="180"/>
<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_likelihood_max_dist" value="2.0"/>
<param name="laser_model_type" value="likelihood_field"/>
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha1" value="0.1"/>
<param name="odom_alpha2" value="0.1"/>
<param name="odom_alpha3" value="0.1"/>
<param name="odom_alpha4" value="0.1"/>
<param name="odom_frame_id" value="odom"/>
<param name="base_frame_id" value="base_footprint"/>
<remap from="map" to="/map" />
</node>
</launch>
Let me know if there is anything else I should provide - this is only my first post. Any help would be appreciated.
Thank you
Asked by apletta on 2019-06-20 05:08:34 UTC
Answers
I think it is because amcl is still looking relative to the namespace for the map (because it is using the service "static_map" per default). Try adding either <param name="use_map_topic" value="true"/>
or <remap from="static_map" to="/static_map" />
to the amcl.launch file, depending on which method for getting the map you want to use. The /map topic is only used when the "use_map_topic" parameter is true. You can see more here: http://wiki.ros.org/amcl
Asked by FOXTER on 2019-06-24 12:20:56 UTC
Comments
Tried both of those, neither seemed to successfully link move_base to /map. Using either of those options, and only one at a time, resulted in the following tf_graph with no /map connection to amcl. I also got that same result when adding both together. What seems to be a step in the right direction is including both but using "map" and "/map" instead of "static_map" and "/static_map". So, adding both of the following lines
<param name="use_map_topic" value="true" />
<remap from="map" to="/map" />
Gives the following tf_graph with /map connected to amcl.
In all cases the nodes were all still connected from tf_prefix/odom and down, but without a top connection to /map, see the tf tree here
Do you think there's more I'd need to do in the move_base launch file?
Asked by apletta on 2019-06-25 02:10:25 UTC
Comments