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

Robot not following path in Nav. Stack

asked 2011-05-16 22:49:21 -0500

mbj gravatar image

Hi community. I'm setting up the navigation stack in my own robot. As I see in a REP, the tf tree is the next:

map -> odom -> chassis_footprint -> chassis -> others (wheels, lasers, ...)

Well, the robot it's represented correctly in rViz (for this, first I launch the robot in gazebo, next I launch the nav. stack and finally I launch the rViz) and furthermore if I set a 2D Goal the robot make a correct path, although the robot doesn't follow it.

Correct path

In addition, if I change the fixed frame - target frame in the rViz to anything that isn't the chassis (like /odom, /map, /chassis_footprint) the robot is saw like this:

Incorrect tf

I think that there be a problem in the tf, but rViz not give any error, although I must say that some frames "jumps" in a rare way.

My tf's are the next:

In tf_broadcaster:

broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.0,0.0,0.0)),ros::Time::now(), "map", "odom"));
broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.0,0.0,0.0)),ros::Time::now(),"chassis_footprint", "chassis"));
broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.12,0.0,0.285)),ros::Time::now(),"chassis", "hokuyo_laser_link"));

In the odometry node:

//since all odometry is 6DOF we'll need a quaternion created from yaw
geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(robot_pose_pa_);

//first, we'll publish the transform over tf
geometry_msgs::TransformStamped odom_trans;
odom_trans.header.stamp = current_time;
odom_trans.header.frame_id = "odom";
odom_trans.child_frame_id = "chassis_footprint";

odom_trans.transform.translation.x = robot_pose_px_;
odom_trans.transform.translation.y = robot_pose_py_;
odom_trans.transform.translation.z = 0.0;
odom_trans.transform.rotation = odom_quat;

//send the transform over /tf
odom_broadcaster.sendTransform(odom_trans);

What is happening and what I'm doing incorrectly? I am very new in the tf's and any idea is appreciated. Thanks!

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
1

answered 2011-05-19 05:50:25 -0500

raphael favier gravatar image

updated 2011-05-19 05:57:02 -0500

Hello,

To me, your problem comes either from wrong parameters for the base controller, and/or a wrong odometry. Could you post your config files for navigation? Check also the twist part of the odometry message, it must be expressed in the local frame of the robot.

Another problem could be that move_base does not output the velocity command on the right topic.

It could also be that your base driver is not working. Did you try controlling your roboy with a joystick or pr2_teleop pr2_teleop_keyboard? That way you could make sure that your base driver is correct and accepts velocity commands.

You should also have a look at this post, which contains a detailed guide to navigation issues.

I hope this helps

Raph

edit flag offensive delete link more

Comments

Hello Raphael. Effectively, the navigation stack expected to receive the speeds on "cmd_vel" topic and I was sending it to another topic. I solved this remapping the correct topics in the move_base.launch. Now, everything is solved, even the tf issue! Thanks.
mbj gravatar image mbj  ( 2011-05-30 00:20:35 -0500 )edit
Hey, glad to see you solved your pbl. Thx for the feedback.
raphael favier gravatar image raphael favier  ( 2011-05-30 00:58:55 -0500 )edit
0

answered 2011-05-17 03:28:28 -0500

dornhege gravatar image

updated 2011-05-17 03:28:39 -0500

It seems that your chassis model is centered at 0 in the z-axis. Your chassis_footprint->chassis transform should thus give the height above ground as the z-component.

Are you also publishing a nav_msgs/Odometry ?

edit flag offensive delete link more

Comments

I answered below, can you have a look? Thanks.
mbj gravatar image mbj  ( 2011-05-18 20:20:37 -0500 )edit
0

answered 2011-05-17 22:23:56 -0500

mbj gravatar image

Hi dornhege, thanks for your answer.

I tried to modify the chassis_footprint -> chassis tf as you said to me and the rare frame "jumps" problem and views it's solved.

tf_broadcaster is now:

broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.0,0.0,0.0)),ros::Time::now(), "map", "odom"));
broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.0,0.0,0.130)),ros::Time::now(),"chassis_footprint", "chassis"));
broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.12,0.0,0.285)),ros::Time::now(),"chassis", "hokuyo_laser_link"));

However, the robot continues without following the path. When I launch the navigation stack and the rViz I don't see any error, only a few warnings like this:

[ WARN] Control loop missed its desired rate of 20.0000Hz... the loop actually took 0.0950 seconds

and this:

[ WARN] Message from [/guardian_odom_node] has a non-fully-qualified frame_id [odom]. Resolved locally to [/odom]. This is will likely not work in multi-robot systems. This message will only print once.

Answering to your question about nav_msgs/Odometry, I have a node that subscribes the joint_states topic, computes the odometry and publish it to the /odom topic.

I moved the robot with the teleop so you can see the diferent frames and path. Do you see anything rare??

path

Thanks!

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-05-16 22:49:21 -0500

Seen: 2,884 times

Last updated: May 19 '11