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

how can we execute a plan via motion planning interface in moveit?

asked 2018-12-17 00:40:55 -0500

MahShah gravatar image

updated 2018-12-17 01:40:43 -0500

gvdhoorn gravatar image

when we use movegroup interface we can execute a plan using

move_group.move();

and in python movegroup intertace we use:

group = moveit_commander.MoveGroupCommander(group_name)
plan = group.go(wait=True)
group.execute(plan, wait=True).

how about when we use motion planning interface?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2018-12-17 05:26:05 -0500

fvd gravatar image

The Motion Planning API tutorial does not answer this, because it stops at visualizing the trajectory.

As commented in this question, you can still use the move_group's execute function with your own plan, for example like this:

// [(continued from the tutorial)...]  
context->solve(res); 
moveit_msgs::MotionPlanResponse response; 
res.getMessage(response); 

// Construct a move_group plan from the planned trajectory
moveit::planning_interface::MoveGroupInterface::Plan myplan;
myplan.trajectory_ = response.trajectory; 
group.execute(myplan);

Otherwise, my understanding is that you can use the interface of your robot/motors, most commonly a JointTrajectoryController advertising a FollowJointTrajectoryAction that you send your trajectory to.

edit flag offensive delete link more

Comments

that is right, thank you

MahShah gravatar image MahShah  ( 2019-02-14 23:38:23 -0500 )edit

thank you help me lots!

ddl_hust gravatar image ddl_hust  ( 2019-04-25 13:31:26 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-12-17 00:40:55 -0500

Seen: 2,110 times

Last updated: Dec 17 '18