MoveIt! violates OrientationConstraint

asked 2021-06-09 14:46:39 -0500

ich4913 gravatar image

updated 2021-06-09 14:54:23 -0500

Hi,

i'm trying to let the UR10's end-effector move to a target pose without changing its end-effector orientation on its way and holding a constant z (height) coordinate.

My problem is, that the robot suddenly stops, changes its confguration and continue its motion. I recorded the behaviour: I recorded the behaviour for you: Video

moveit_msgs::OrientationConstraint ocm;
ocm.link_name = "ur10_wrist_3_link";
ocm.header.frame_id = "ur10_base_link";
ocm.orientation.w = 0.707;
ocm.orientation.x = -0.707;
ocm.absolute_x_axis_tolerance = 0.01;
ocm.absolute_y_axis_tolerance = 0.01;
ocm.absolute_z_axis_tolerance = 0.01;
ocm.weight = 1.0;

moveit_msgs::Constraints test_constraints;
test_constraints.orientation_constraints.push_back(ocm);
move_group_interface.setPathConstraints(test_constraints);

...


success = (move_group_interface.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);

Why does MoveIt! violate this constraint without mention it in any way? Is there a better option to realize such constraints?

Do I perhaps have to use some other stuff? Some guys mentioned trac_ik or talked about OMPL is not good for that, try Descartes or MoveItServo? An other website told to set enforce_constrained_planning in the ompl_planning.yaml file in the moveit_config, but it does not work. Isn't it possible to do it like that, with MoveIt!, OMPL, i think i'm using SBL?

Can you recommend a way to realize the constrainted motion?

In summary i need someone to make the ee of the arm move in a constant direction without changing the orientation or the z-coordinate and make me know if this constraint can not be held.

edit retag flag offensive close merge delete