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

end-effector pose constrained planning

asked 2014-06-19 12:59:21 -0600

Victor22 gravatar image

updated 2014-06-19 13:01:56 -0600

Hello: I am looking for end-effector pose constrained planning for the manipulator. I know that such functionalities have been provided in "MoveIt!" where you set your kinematics constraints and then give command to plan a path.

I believe that this type of end-effector constrained planning (in MoveIt!) is done in end-effector cartesian degree of freedom using Inverse Kinematics.

Can anyone please point me to: where this task-constrained code sits in OMPL (as MoveIt uses OMPL), or any pointer to the research paper of this implementation in MoveIt!

I want to understand how it is done and what are the steps involved in ROS implementation.

Thanks.

edit retag flag offensive close merge delete

Comments

Hello! I am also very interested in manipulator constraint motion planning, and have some problem about how moveit sent constraint information to ompl, and how ompl deal with it, if you have solve it, please help me, any help is very greatful!

Rob.Chen gravatar image Rob.Chen  ( 2019-01-08 08:15:16 -0600 )edit

@Rob.Chen Hi! Did you make progress on your question? I have the same confusion as you.

JohnDoe gravatar image JohnDoe  ( 2023-07-18 02:34:09 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2015-05-28 04:01:07 -0600

fivef gravatar image

updated 2019-03-04 06:23:19 -0600

Here is an example of how to use path constraints (here orientation constraints) with Moveit in Python:

from moveit_msgs.msg import RobotState, Constraints, OrientationConstraint

def init_upright_path_constraints(self,pose):

    self.upright_constraints = Constraints()
    self.upright_constraints.name = "upright"
    orientation_constraint = OrientationConstraint()
    orientation_constraint.header = pose.header
    orientation_constraint.link_name = self.arm.get_end_effector_link()
    orientation_constraint.orientation = pose.pose.orientation
    orientation_constraint.absolute_x_axis_tolerance = 0.4
    orientation_constraint.absolute_y_axis_tolerance = 0.4
    orientation_constraint.absolute_z_axis_tolerance = 0.4
    #orientation_constraint.absolute_z_axis_tolerance = 3.14 #ignore this axis
    orientation_constraint.weight = 1

    self.upright_constraints.orientation_constraints.append(orientation_constraint)


def enable_upright_path_constraints(self):
    self.arm.set_path_constraints(self.upright_constraints)

def disable_upright_path_constraints(self):
    self.arm.set_path_constraints(None)
edit flag offensive delete link more

Comments

from moveit_msgs.msg import RobotState, Constraints, OrientationConstraint is import line

danjo gravatar image danjo  ( 2018-10-03 19:09:34 -0600 )edit

what is pose here?

Mehdi. gravatar image Mehdi.  ( 2019-01-27 17:16:43 -0600 )edit

pose is the geometry_msgs/Pose of the endeffector right before you enable the path constraints.

fivef gravatar image fivef  ( 2019-03-04 06:26:11 -0600 )edit

I can confirm that the pose var type is geometry_msgs/PoseStamped and not geometry_msgs/Pose. geometry_msgs/Pose has no header. :)

AdriaArroyo gravatar image AdriaArroyo  ( 2021-02-10 06:59:03 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2014-06-19 12:59:21 -0600

Seen: 2,827 times

Last updated: Mar 04 '19