Skip to content

how to set orientation constraint in connect stage? #682

Open
@amoyalang

Description

@amoyalang

When I perform the grasping and placing actions, I hope that the clamped object will not tilt during the process of moving to the placing position. Therefore, I added path constraints in theconnetstage, which led to the planning always failing. I need to consult everyone, so I used the panda robot to simulate my process of setting path constraints, and the result was also a planning failure.

I use this demo reproduct problem. I only added orientation constraints in the connect stage. The following is my connect stage code and my understanding of direction constraints.

{
        moveit_msgs::msg::OrientationConstraint &c =
        path_constraints.orientation_constraints[0];
        c.link_name = "panda_hand";
        c.header.frame_id = "panda_link0";
        c.orientation.w = 1.0;

        //When grasping object,X axis is upright, 
        //so the X axis could be rotated,it is tolerancec omplete freedom,ohter tolerances shouble be constrained
        c.absolute_x_axis_tolerance = M_PI;
        c.absolute_y_axis_tolerance = M_PI / 10;
        c.absolute_z_axis_tolerance = M_PI / 10;
        c.parameterization = moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES;
        c.weight = 1.0;
}

When an object is being clamped, the X-axis of panda_hand is upward. I don't want the X-axis of panda_hand to deviate during the movement process. Therefore, I think it is not allowed to rotate significantly around the y and z axes, but it can rotate freely around the X-axis. My code is written based on this idea.

Image
This has led to its inability to plan successfully.
Why is this?

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions