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

Help with Navigation - Error "transform from /base_link to /map"

asked 2012-06-06 08:44:01 -0600

updated 2012-06-06 08:45:50 -0600

Hello There!

I am having a hard time to get the Navigation Stack running on a robot (Traxbot), to which it was added an Hokuyo laser sensor.

I was able to follow the navigation tutorial smoothly, broadcasting the base_laser→base_link transform, publishing a sensor_msgs/LaserScan using hokuyo_node, publishing the nav_msgs/Odometry message over ROS and a transforming from a "/odom" coordinate frame to "/base_link", as well as receiving velocity commands and passing them on to the robot. I have also created a very simple map of a square arena.

All of these issues have been tested and seem to be working just fine.

Then, I have created the launch file to bring up the robot's configurations as well as the navigation stack (with AMCL), following the tutorial instructions.

So, when I roslaunch my "traxbot_config.launch", everything works fine:

NODES
 /
  robot_node (traxbot_robot/robot_node)
  hokuyo_node (hokuyo_node/hokuyo_node)
  traxbot_static_tf_laser (mrl_tf_setup/traxbot_static_tf_laser)

  ROS_MASTER_URI=http://localhost:11311

  core service [/rosout] found
  process[robot_node-1]: started with pid [8014]
  process[hokuyo_node-2]: started with pid [8015]
  process[traxbot_static_tf_laser-3]: started with pid [8016]
  [ WARN] [1338989473.365252155]: The use_rep_117 parameter has not been set or is set to false.  Please see: http://ros.org/wiki/rep_117/migration
  [ INFO] [1338989473.518591684]: Robot -- Successfully connected to the Robot!

Then, I roslaunch the navstack ("move_base_square_map.launch"), and I get the following output:

NODES
 /
   map_server (map_server/map_server)
   amcl (amcl/amcl)
   move_base (move_base/move_base)

   ROS_MASTER_URI=http://localhost:11311

   core service [/rosout] found
   process[map_server-1]: started with pid [2187]
   process[amcl-2]: started with pid [2188]
   process[move_base-3]: started with pid [2189]
   [ INFO] [1339006055.653083864]: Subscribed to Topics: laser_scan_sensor
   [ INFO] [1339006055.681022434]: Requesting the map...
   [ INFO] [1339006055.683225249]: Still waiting on map...
   [ INFO] [1339006056.684127276]: Still waiting on map...
   [ WARN] [1339006057.693208432]: You have set map parameters, but also requested to use the static map. Your parameters will be overwritten by those given by the map server
   [ INFO] [1339006057.694168703]: Received a 200 X 200 map at 0.005000 m/pix
   [ WARN] [1339006062.734650906]: Waiting on transform from /base_link to /map to become available before running costmap, tf error: 
   [ WARN] [1339006067.778188511]: Waiting on transform from /base_link to /map to become available before running costmap, tf error: 
   [ WARN] [1339006072.821525895]: Waiting on transform from /base_link to /map to become available before running costmap, tf error: 
   [ WARN] [1339006077.858041067]: Waiting on transform from /base_link to /map to become available before running costmap, tf error: 
   [ WARN] [1339006082.896098542]: Waiting on transform from /base_link to /map to become available before running costmap, tf error: 
   [ WARN] [1339006087.945294010]: Waiting on transform from /base_link to /map to become available before running costmap, tf error: 
   [ WARN] [1339006093.020568219]: Waiting on transform from /base_link to /map to become available before running costmap, tf error: 
   [ WARN] [1339006098.075362691]: Waiting on transform from /base_link to /map to become available before running costmap, tf error:

Note that after "error:" there is no information as it usually exists when this warning msg shows up (e.g., here).

So I have analyzed all the param files to check ... (more)

edit retag flag offensive close merge delete

5 Answers

Sort by » oldest newest most voted
4

answered 2012-06-11 07:14:01 -0600

So...after a while, I ended up solving the problem of bringing up the Nav Stack today. The problem was in the "costmap_common_params.yaml" file.

Basically I was setting the robot footprint in cms, instead of using meters. So I was defining a robot that would have a larger size than the map itself :D

Apparently, that was enough for not running the costmap and blow the whole thing up.

Thank you everyone for your feedback!

edit flag offensive delete link more
2

answered 2012-06-06 09:33:43 -0600

DimitriProsser gravatar image

You need to publish a map frame. If I'm correct, your problem is that AMCL is looking for the /map frame when it loads your static map from the map_server. In order to resolve this problem, you must either set the frame_id of your map_server to /odom or publish the /map frame as a parent frame to /odom.

<node name="map_node" pkg="map_server" type="map_server" args="$(find my_package)/config/map.yaml" respawn="false">
    <param name="frame_id" value="/odom" />
</node>
edit flag offensive delete link more

Comments

2

Thank you for your answer Dmitri! Unfortunately, I can only look into it on Monday and I will report about the problem then. Hope it works :)

DavidPortugal gravatar image DavidPortugal  ( 2012-06-08 01:35:42 -0600 )edit
2

answered 2012-06-10 09:24:54 -0600

So, I have tried Dmitri's suggestion (setting /odom as frame_id of the map server), but the same error persists.

How could I explicitly publish the /map frame as a parent frame to /odom? Shouldn't the AMCL be responsible for this transformation?

I've also played around with the AMCL parameter use_map_topic, but had no luck.

I am able to bring up the navstack with stage and a static map. Stage is responsible for /odom -> /base_footprint -> /base_link -> /base_laser_link transformations, while AMCL deals with /map -> /odom.

Using the robot, my robot_node takes care of /odom -> /base_link transformation, and I have a static tf_broadcaster taking care of /base_link -> /laser. But the tf from /map to /odom does not exist =(

I've compared all the parameters (AMCL, Local Planner, Global and Local Costmap) but I am not able to find anything suspicious...

Help please!

edit flag offensive delete link more

Comments

2

Additionally, when i run:

tf tf_echo /map /base_link

or

tf tf_echo /map /odom

I receive the following result:

Failure at 1339364192.954729563
Exception thrown:Frame id /map does not exist! Frames (4): Frame /base_link exists with parent /odom.
Frame /odom exists with parent N
DavidPortugal gravatar image DavidPortugal  ( 2012-06-10 11:44:17 -0600 )edit
2
Failure at 1339364192.954729563
Exception thrown:Frame id /map does not exist! Frames (4): Frame /base_link exists with parent /odom.
Frame /odom exists with parent NO_PARENT.
Frame /laser exists with parent /base_link.
DavidPortugal gravatar image DavidPortugal  ( 2012-06-10 11:45:15 -0600 )edit
2
The current list of frames is:
Frame /base_link exists with parent /odom.
Frame /odom exists with parent NO_PARENT.
Frame /laser exists with parent /base_link.
DavidPortugal gravatar image DavidPortugal  ( 2012-06-10 11:45:31 -0600 )edit
1

please, be aware that answers.ros it is not a forum, so it is wrong to post your updates or comments as a new answer. cheers

Procópio gravatar image Procópio  ( 2012-06-10 12:01:24 -0600 )edit
2

Sorry for that, just wanted to bring in more info to help solving the problem.

DavidPortugal gravatar image DavidPortugal  ( 2012-06-10 12:21:41 -0600 )edit

I think a more legit way is shifting whatever you are writing here as comments of your original post or just simply edit the original (and adding different edit titles so ppl can trace our progress as well). Mid

Midnight gravatar image Midnight  ( 2013-05-19 20:00:38 -0600 )edit

To explicitly publish /map frame as a parent to /odom frame, one can use the following command- rosrun tf tf 0 0 0 0 0 0 /map /odom 100 , where {0 , 0 , 0} -> translational transform, and {0 0 0 } -> rotational transform

skpro19 gravatar image skpro19  ( 2018-06-26 08:44:08 -0600 )edit
1

answered 2012-06-10 11:59:07 -0600

Procópio gravatar image

Are you setting your robot initial pose? That's one way you can get your /map to /odom transformation. AMCL will only correct that transformation based on other sensor readings.

edit flag offensive delete link more

Comments

2

Yes, at the AMCL launch file: <param name="initial_pose_x" value="0.1"/> <param name="initial_pose_y" value="0.1"/> <param name="initial_pose_a" value="1.571"/>

I can also see the map in Rviz, but I get the following error there: .Global Status: Error Fixed Frame [/map] does not exist

DavidPortugal gravatar image DavidPortugal  ( 2012-06-10 12:20:00 -0600 )edit
0

answered 2012-06-10 13:14:31 -0600

cagatay gravatar image

updated 2012-06-10 13:16:44 -0600

David, AMCL does not provide any tf transform from map to odom according to amcl's wiki while gmapping does. So in my opinion you have to figure out a way to broadcast the /map as a tf.

btw: I am a beginner i don't want to mislead you

edit flag offensive delete link more

Comments

2

Dear Cagatay, thank you for your reply. As you can see here, when I bring up the navstack using stage, I get the following tf_tree: https://dl.dropbox.com/u/691928/patrolsim_frames.pdf. You can see that /map is the parent frame of /odom, being broadcasted by AMCL.

DavidPortugal gravatar image DavidPortugal  ( 2012-06-10 13:33:39 -0600 )edit
2

However in my current case, I get the following tf_tree:

https://dl.dropbox.com/u/691928/frames.pdf

DavidPortugal gravatar image DavidPortugal  ( 2012-06-10 13:34:28 -0600 )edit

how about trying to broadcast just only /map frame to see whether you can or not ignoring other transforms.

cagatay gravatar image cagatay  ( 2012-06-10 13:59:42 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2012-06-06 08:44:01 -0600

Seen: 21,297 times

Last updated: Jun 11 '12