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

MoveIt FollowJointTrajectoryFeedback - What happens with it?

asked 2014-05-27 23:31:49 -0600

Rabe gravatar image

Hey guys,

I am writing a controller for a robot. I managed to get it running with MoveIt and Rviz, I have a JointStatePublisher running and can plan trajectories. Most of the times the robot moves along the desired path ;)

In the "Follow_Joint_Trajectory" topic, I get my goals and can post my feedback. Now I was wondering, what exactly happens to the feedback? The messages has arrays for everything like current position, desired position and error. When I'm putting random high values in the error array, I was expecting MoveIt to cancel the movement? Or replan it?

So far, I only get preempt-requests, when my robot moves too slow and exceeds the timeframe given from MoveIt. Are the feedback values from my robot used for anything or is it just a placeholder? Another option might be, that my statepublisher "overrides" the feedback from my controller? Since the data from the statepublisher agrees with the planned trajectory, MoveIt could ignore the "wrong" feedback?

Thanks in advance,

Rabe

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2014-05-28 00:01:58 -0600

fergs gravatar image

It really depends on what controller manager you are using in MoveIt. If you are using the moveit_simple_controller_manager plugin, then it basically ignores the feedback entirely, and only uses the result message. The move_group node itself will preempt the controller if it is taking too long (so that will always happen, regardless of the controller manager plugin selected).

Normally, the controller would actually stop itself if the error gets too high on a particular joint. "too high" would typically be specified in the action goal, in the goal_tolerance and path_tolerance vectors, but this may not be filled in by MoveIt.

edit flag offensive delete link more

Comments

Thanks, yes I am using the simple controller manager. My guess is, that I haven't fully understood the underlying concept yet, since at the moment I have an actionServer, which then tells my controller what to do. But it seems I am leaving out the step of the ROS Controller Manager? Thanks anyway!

Rabe gravatar image Rabe  ( 2014-05-28 05:45:04 -0600 )edit

The "moveit simple controller manager" is really poorly named, but is named to follow the conventions of MoveIt. It is in fact, not a controller nor a manager. Instead, it basically converts MoveIt trajectories into commands to send to actual controllers that are running external from moveit.

fergs gravatar image fergs  ( 2014-05-29 20:59:50 -0600 )edit

If you are also using the "ros_control" package, then you might have a second controller manager, unrelated to the moveit one. This controller_manager actually manages (as in load, unload, start, stop) the controllers that you have defined for your robot.

fergs gravatar image fergs  ( 2014-05-29 21:00:44 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2014-05-27 23:31:49 -0600

Seen: 1,304 times

Last updated: May 28 '14