Robot.constraints_from_configuration
-
Robot.
constraints_from_configuration
(configuration, tolerances_above, tolerances_below, group=None)[source] Create joint constraints for all joints of the configuration.
- Parameters
configuration (
Configuration
) – The target configuration.tolerances_above (
list
offloat
) – The tolerances above the targeted configuration’s joint value on each of the joints, defining the upper bound in radians to be achieved. If only one value is passed, it will be used to create upper bounds for all joint constraints.tolerances_below (
list
offloat
) – The tolerances below the targeted configuration’s joint value on each of the joints, defining the upper bound in radians to be achieved. If only one value is passed, it will be used to create lower bounds for all joint constraints.group (
str
, optional) – The planning group for which we specify the constraint. Defaults to the robot’s main planning group.
- Returns
- Raises
ValueError – If the passed configuration does not correspond to the group.
ValueError – If the passed list of tolerance values have a different length than the configuration.
Notes
Make sure that you are using the correct tolerance units if your robot has different joint types defined.
Examples
>>> configuration = Configuration.from_revolute_values([-0.042, 4.295, -4.110, -3.327, 4.755, 0.]) >>> tolerances_above = [math.radians(1)] * 6 >>> tolerances_below = [math.radians(1)] * 6 >>> group = robot.main_group_name >>> robot.constraints_from_configuration(configuration, tolerances_above, tolerances_below, group) [JointConstraint('shoulder_pan_joint', -0.042, 0.017453292519943295, 0.017453292519943295, 1.0), JointConstraint('shoulder_lift_joint', 4.295, 0.017453292519943295, 0.017453292519943295, 1.0), JointConstraint('elbow_joint', -4.11, 0.017453292519943295, 0.017453292519943295, 1.0), JointConstraint('wrist_1_joint', -3.327, 0.017453292519943295, 0.017453292519943295, 1.0), JointConstraint('wrist_2_joint', 4.755, 0.017453292519943295, 0.017453292519943295, 1.0), JointConstraint('wrist_3_joint', 0.0, 0.017453292519943295, 0.017453292519943295, 1.0)]