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

How can I execute a moveit_msgs::RobotTrajectory that I have on file?

asked 2018-07-12 11:52:30 -0500

Levi_Manring gravatar image

updated 2018-07-12 14:13:27 -0500

I am trying to execute a RobotTrajectory on a MoveGroup that I have predefined. I have tried stuff like

group.execute(myRobotTrajectory)

and

trajectory_execution_manager::TrajectoryExecutionManager::push(myRobotTrajectory);
trajectory_execution_manager::TrajectoryExecutionManager::execute();

and

move_group::MoveGroupExecuteTrajectoryAction(myRobotTrajectory);

I think the last one is the closest, but it says that the action isn't recognized. Any tips?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-07-12 15:12:27 -0500

Levi_Manring gravatar image

Ok, so this is what I did to solve this issue.

I created a fake plan, then populated the .trajectory_ with my robot trajectory. Then I executed. Here is my code:

      moveit::planning_interface::MoveGroup::Plan my_plan2;
      my_plan2.trajectory_ = *myRobotTrajectory;
      group.execute(my_plan2);
edit flag offensive delete link more

Comments

I tried executing a planned trajectory one more time using

move_group.execute(my_plan);

that was computed successfully, but the robot doesn't move in rviz, although in the terminal it says

Fake execution of trajectory

Completed trajectory execution with status SUCCEEDED ...

any tips? thanks

hooman gravatar image hooman  ( 2019-02-12 20:09:06 -0500 )edit

@hooman this is a Q&A site, not a forum. Please ask this as a new question and provide as many of the relevant details about your setup as you can. (ROS version, Robot type and version, any tutorials you're following or specific programs you're trying to run).

ahendrix gravatar image ahendrix  ( 2019-02-12 22:03:48 -0500 )edit

If you ask this as a new question, it will be seen by a much larger number of people and you're more likely to get a good answer.

ahendrix gravatar image ahendrix  ( 2019-02-12 22:04:25 -0500 )edit

thanks, I'll post a new question.

hooman gravatar image hooman  ( 2019-02-13 11:36:07 -0500 )edit

@hooman I am facing the same issue, did you figure it out ? Thanks

edote gravatar image edote  ( 2020-04-24 12:37:10 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2018-07-12 11:52:30 -0500

Seen: 758 times

Last updated: Jul 12 '18