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

Does move_group.plan(sampleJointTargetPose) implement MoveJ by default?

asked 2020-12-07 15:50:18 -0500

srujan gravatar image

I am using a UR10 real robot. I am not using Universal_Robots_ROS_Driver for robot control. I am using moveit move_group to do collision check for a pair of start_state and goal_state in joint-space. I am simply using move_group.plan() method to figure out if a collision-free path exists between the two states. It works. But, we control the robot using MoveJ commands, So I am trying to figure out if the collision-free path that is generated by the move_group.plan() and the paths that are in-general generated by MoveJ command are both same?

If not, what is the correct way of doing this?

if yes, is there a better way to do this?

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
2

answered 2020-12-08 23:19:17 -0500

fvd gravatar image

move_group.plan() and the MoveJ command are not the same. MoveJ moves directly to the target in joint space (PTP motion), while move_group.plan() submits a planning request to whichever planning plugin is connected to MoveIt. The default planning plugin is sampling-based (RRTConnect in OMPL), but when there are no obstacles, it returns a direct motion in joint space just like MoveJ, which is probably the source of your confusion. If there are obstacles, the result of move_group.plan() can be very different from MoveJ.

If you want to plan motions like MoveJ (linear in joint space/configuration space) and MoveL (linear in cartesian space), you can use the pilz_industrial_motion_planner plugin which was recently merged into MoveIt. It has not been backported to melodic yet, so you would need to build MoveIt from source. I suggest using an underlay workspace (more details) with MoveIt inside to alleviate build time.

If you send a PTP motion planning request to the pilz_industrial_motion_planner plugin and the plan succeeds, then moving your robot with the MoveJ command to the same target should be safe (if you represented your whole scene correctly and did not make mistakes).

In theory you could also çreate your own RobotTrajectory by linearly interpolating the joint poses between your start and goal and then check if the path is valid, but I would use the industrial motion planning plugin as described above, to avoid duplicating work. Using PTP/LIN/CIRC motions in MoveIt should soon become a lot easier.

edit flag offensive delete link more

Comments

Thanks for your response @fvd. It was indeed useful. However, I am unable to use the pilz_industrial_motion_planner plugin. Here's what I did: - created a new workspace with moveit melodic-devel build from source. build successful - created a new workspace (pilz_ws) and underlayed melodic_source_moveit1. I installed pilz_common and pilz_industrial_motion packages, build successful. tried installing pilz_robots . build unsuccessful, hence discarded it for time being - Copied pilz_industrial_motion_planner_planning_pipeline.launch.xml from the prbt_moveit_config/launch to my aris_metra_scan_config/launch. - Created cartesian_limits.yaml file in the aris_metra_scan_config/config - In aris_metra_scan_config/demo.launch, I changed <arg name="pipeline" default="ompl" /> to <arg name="pipeline" default="pilz_industrial_motion_planner" /> when I launch demo.launch, I get MoveGroup running was unable to load pilz_industrial_motion_planner::CommandPlanner. Help

srujan gravatar image srujan  ( 2020-12-14 18:57:22 -0500 )edit

Since comments are not meant for new questions, please accept this answer and post a new question with your new problem.

Try following this tutorial: https://ros-planning.github.io/moveit... And note that you might have to build from the master branch at the moment.

fvd gravatar image fvd  ( 2020-12-14 21:53:52 -0500 )edit

That tutorial didn't help. However my issue is resolved now. I copied pilz_command_planner_planning_pipeline.launch.xml from the prbt_moveit_config/launch to my aris_metra_scan_config/launch

and made the following change in aris_metra_scan_config/demo.launch

  • <arg name="pipeline" default="ompl" /> to <arg name="pipeline" default="pilz_command_planner" />

This solved the issue.

@fvd, do I still add a new question for this?

srujan gravatar image srujan  ( 2020-12-14 22:21:09 -0500 )edit

If it's solved, then no (although if the tutorial is insufficient you could try fixing it). Just remember to use comments for clarifications for the future and make a new post for new questions, so that others can find it more easily.

fvd gravatar image fvd  ( 2020-12-14 22:33:43 -0500 )edit

I agree and will surely make a new post for new questions in future. Thank you!

srujan gravatar image srujan  ( 2020-12-14 22:40:33 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-12-07 15:50:18 -0500

Seen: 199 times

Last updated: Dec 08 '20