Classes | Functions | Variables
kinematic_constraints Namespace Reference

Representation and evaluation of kinematic constraints. More...

Classes

struct  ConstraintEvaluationResult
 Struct for containing the results of constraint evaluation. More...
 
class  JointConstraint
 Class for handling single DOF joint constraints. More...
 
class  KinematicConstraint
 Base class for representing a kinematic constraint. More...
 
class  KinematicConstraintSet
 A class that contains many different constraints, and can check RobotState *versus the full set. A set is satisfied if and only if all constraints are satisfied. More...
 
class  OrientationConstraint
 Class for constraints on the orientation of a link. More...
 
class  PositionConstraint
 Class for constraints on the XYZ position of a link. More...
 
class  VisibilityConstraint
 Class for constraints on the visibility relationship between a sensor and a target. More...
 

Functions

template<typename Derived >
std::tuple< Eigen::Matrix< typename Eigen::MatrixBase< Derived >::Scalar, 3, 1 >, bool > CalcEulerAngles (const Eigen::MatrixBase< Derived > &R)
 
static bool collectConstraints (XmlRpc::XmlRpcValue &params, moveit_msgs::Constraints &constraints)
 
static bool constructConstraint (XmlRpc::XmlRpcValue &params, moveit_msgs::JointConstraint &constraint)
 
static bool constructConstraint (XmlRpc::XmlRpcValue &params, moveit_msgs::OrientationConstraint &constraint)
 
static bool constructConstraint (XmlRpc::XmlRpcValue &params, moveit_msgs::PositionConstraint &constraint)
 
static bool constructConstraint (XmlRpc::XmlRpcValue &params, moveit_msgs::VisibilityConstraint &constraint)
 
bool constructConstraints (XmlRpc::XmlRpcValue &params, moveit_msgs::Constraints &constraints)
 extract constraint message from XmlRpc node. More...
 
moveit_msgs::Constraints constructGoalConstraints (const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance=std::numeric_limits< double >::epsilon())
 Generates a constraint message intended to be used as a goal constraint for a joint group. The full constraint will contain a vector of type JointConstraint, one for each DOF in the group. More...
 
moveit_msgs::Constraints constructGoalConstraints (const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
 Generates a constraint message intended to be used as a goal constraint for a joint group. The full constraint will contain a vector of type JointConstraint, one for each DOF in the group. More...
 
moveit_msgs::Constraints constructGoalConstraints (const std::string &link_name, const geometry_msgs::Point &reference_point, const geometry_msgs::PointStamped &goal_point, double tolerance=1e-3)
 Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint message will contain only a PositionConstraint. A sphere will be used to represent the constraint region. More...
 
moveit_msgs::Constraints constructGoalConstraints (const std::string &link_name, const geometry_msgs::PointStamped &goal_point, double tolerance=1e-3)
 Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint message will contain only a PositionConstraint. A sphere will be used to represent the constraint region. More...
 
moveit_msgs::Constraints constructGoalConstraints (const std::string &link_name, const geometry_msgs::PoseStamped &pose, const std::vector< double > &tolerance_pos, const std::vector< double > &tolerance_angle)
 Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint will contain a PositionConstraint and a OrientationConstraint, constructed from the pose. A box will be used to represent the constraint region for the PositionConstraint. More...
 
moveit_msgs::Constraints constructGoalConstraints (const std::string &link_name, const geometry_msgs::PoseStamped &pose, double tolerance_pos=1e-3, double tolerance_angle=1e-2)
 Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint will contain a PositionConstraint and a OrientationConstraint, constructed from the pose. A sphere will be used to represent the constraint region for the PositionConstraint. More...
 
moveit_msgs::Constraints constructGoalConstraints (const std::string &link_name, const geometry_msgs::QuaternionStamped &quat, double tolerance=1e-2)
 Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint message will contain only an OrientationConstraint. More...
 
static bool constructPoseStamped (XmlRpc::XmlRpcValue::iterator &it, geometry_msgs::PoseStamped &pose)
 
std::size_t countIndividualConstraints (const moveit_msgs::Constraints &constr)
 
static ConstraintEvaluationResult finishPositionConstraintDecision (const Eigen::Vector3d &pt, const Eigen::Vector3d &desired, const std::string &name, double weight, bool result, bool verbose)
 
bool isEmpty (const moveit_msgs::Constraints &constr)
 Check if any constraints were specified. More...
 
moveit_msgs::Constraints mergeConstraints (const moveit_msgs::Constraints &first, const moveit_msgs::Constraints &second)
 Merge two sets of constraints into one. More...
 
 MOVEIT_CLASS_FORWARD (JointConstraint)
 
 MOVEIT_CLASS_FORWARD (KinematicConstraint)
 
 MOVEIT_CLASS_FORWARD (KinematicConstraintSet)
 
 MOVEIT_CLASS_FORWARD (OrientationConstraint)
 
 MOVEIT_CLASS_FORWARD (PositionConstraint)
 
 MOVEIT_CLASS_FORWARD (VisibilityConstraint)
 
static double normalizeAbsoluteAngle (const double angle)
 
static double normalizeAngle (double angle)
 
bool resolveConstraintFrames (const moveit::core::RobotState &state, moveit_msgs::Constraints &constraints)
 Resolves frames used in constraints to links in the robot model. More...
 

Variables

const std::string LOGNAME = "kinematic_constraint_utils"
 

Detailed Description

Representation and evaluation of kinematic constraints.

Function Documentation

◆ CalcEulerAngles()

template<typename Derived >
std::tuple<Eigen::Matrix<typename Eigen::MatrixBase<Derived>::Scalar, 3, 1>, bool> kinematic_constraints::CalcEulerAngles ( const Eigen::MatrixBase< Derived > &  R)

This's copied from https://gitlab.com/libeigen/eigen/-/blob/master/unsupported/Eigen/src/EulerAngles/EulerSystem.h#L187 Return the intrinsic Roll-Pitch-Yaw euler angles given the input rotation matrix and boolean indicating whether the there's a singularity in the input rotation matrix (true: the input rotation matrix don't have a singularity, false: the input rotation matrix have a singularity) The returned angles are in the ranges [-pi:pi]x[-pi/2:pi/2]x[-pi:pi]

Definition at line 110 of file kinematic_constraint.cpp.

◆ collectConstraints()

static bool kinematic_constraints::collectConstraints ( XmlRpc::XmlRpcValue params,
moveit_msgs::Constraints &  constraints 
)
static

Definition at line 480 of file utils.cpp.

◆ constructConstraint() [1/4]

static bool kinematic_constraints::constructConstraint ( XmlRpc::XmlRpcValue params,
moveit_msgs::JointConstraint &  constraint 
)
static

Definition at line 300 of file utils.cpp.

◆ constructConstraint() [2/4]

static bool kinematic_constraints::constructConstraint ( XmlRpc::XmlRpcValue params,
moveit_msgs::OrientationConstraint &  constraint 
)
static

Definition at line 405 of file utils.cpp.

◆ constructConstraint() [3/4]

static bool kinematic_constraints::constructConstraint ( XmlRpc::XmlRpcValue params,
moveit_msgs::PositionConstraint &  constraint 
)
static

Definition at line 347 of file utils.cpp.

◆ constructConstraint() [4/4]

static bool kinematic_constraints::constructConstraint ( XmlRpc::XmlRpcValue params,
moveit_msgs::VisibilityConstraint &  constraint 
)
static

Definition at line 443 of file utils.cpp.

◆ constructConstraints()

bool kinematic_constraints::constructConstraints ( XmlRpc::XmlRpcValue params,
moveit_msgs::Constraints &  constraints 
)

extract constraint message from XmlRpc node.

This can be used to construct a Constraints message from specifications uploaded on the parameter server.

Parameters
[in]paramsXmlRpc node of the parameter specification
[out]constraintsThe constructed constraints message
Returns
was the construction successful?

Definition at line 523 of file utils.cpp.

◆ constructGoalConstraints() [1/7]

moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints ( const moveit::core::RobotState state,
const moveit::core::JointModelGroup jmg,
double  tolerance = std::numeric_limits<double>::epsilon() 
)

Generates a constraint message intended to be used as a goal constraint for a joint group. The full constraint will contain a vector of type JointConstraint, one for each DOF in the group.

Parameters
[in]stateThe state from which to generate goal joint constraints
[in]jmgThe group for which to generate joint constraints
[in]toleranceA tolerance to apply both above and below for all constraints
Returns
A full constraint message containing all the joint constraints

Definition at line 130 of file utils.cpp.

◆ constructGoalConstraints() [2/7]

moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints ( const moveit::core::RobotState state,
const moveit::core::JointModelGroup jmg,
double  tolerance_below,
double  tolerance_above 
)

Generates a constraint message intended to be used as a goal constraint for a joint group. The full constraint will contain a vector of type JointConstraint, one for each DOF in the group.

Parameters
[in]stateThe state from which to generate goal joint constraints
[in]jmgThe group for which to generate goal joint constraints
[in]tolerance_belowThe below tolerance to apply to all constraints
[in]tolerance_aboveThe above tolerance to apply to all constraints
Returns
A full constraint message containing all the joint constraints

Definition at line 136 of file utils.cpp.

◆ constructGoalConstraints() [3/7]

moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints ( const std::string &  link_name,
const geometry_msgs::Point &  reference_point,
const geometry_msgs::PointStamped &  goal_point,
double  tolerance = 1e-3 
)

Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint message will contain only a PositionConstraint. A sphere will be used to represent the constraint region.

Parameters
[in]link_nameThe link name for the PositionConstraint
[in]reference_pointA point corresponding to the target_point_offset of the PositionConstraint
[in]goal_pointThe position associated with the constraint region
[in]toleranceThe radius associated with the sphere volume associated with the constraint region
Returns
A full constraint message containing the position constraint

Definition at line 247 of file utils.cpp.

◆ constructGoalConstraints() [4/7]

moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints ( const std::string &  link_name,
const geometry_msgs::PointStamped &  goal_point,
double  tolerance = 1e-3 
)

Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint message will contain only a PositionConstraint. A sphere will be used to represent the constraint region.

Parameters
[in]link_nameThe link name for the PositionConstraint
[in]goal_pointThe position associated with the constraint region
[in]toleranceThe radius associated with the sphere volume associated with the constraint region
Returns
A full constraint message containing the position constraint

Definition at line 237 of file utils.cpp.

◆ constructGoalConstraints() [5/7]

moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints ( const std::string &  link_name,
const geometry_msgs::PoseStamped &  pose,
const std::vector< double > &  tolerance_pos,
const std::vector< double > &  tolerance_angle 
)

Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint will contain a PositionConstraint and a OrientationConstraint, constructed from the pose. A box will be used to represent the constraint region for the PositionConstraint.

Parameters
[in]link_nameThe link name for both constraints
[in]poseThe pose stamped to be used for the target region.
[in]tolerance_posThe dimensions of the box (xyz) associated with the target region of the PositionConstraint
[in]tolerance_angleThe values to assign to the absolute tolerances (xyz) of the OrientationConstraint
Returns
A full constraint message containing both constraints

Definition at line 197 of file utils.cpp.

◆ constructGoalConstraints() [6/7]

moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints ( const std::string &  link_name,
const geometry_msgs::PoseStamped &  pose,
double  tolerance_pos = 1e-3,
double  tolerance_angle = 1e-2 
)

Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint will contain a PositionConstraint and a OrientationConstraint, constructed from the pose. A sphere will be used to represent the constraint region for the PositionConstraint.

Parameters
[in]link_nameThe link name for both constraints
[in]poseThe pose stamped to be used for the target region.
[in]tolerance_posThe dimension of the sphere associated with the target region of the PositionConstraint
[in]tolerance_angleThe value to assign to the absolute tolerances of the OrientationConstraint
Returns
A full constraint message containing both constraints

Definition at line 156 of file utils.cpp.

◆ constructGoalConstraints() [7/7]

moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints ( const std::string &  link_name,
const geometry_msgs::QuaternionStamped &  quat,
double  tolerance = 1e-2 
)

Generates a constraint message intended to be used as a goal constraint for a given link. The full constraint message will contain only an OrientationConstraint.

Parameters
[in]link_nameThe link name for the OrientationConstraint
[in]quatThe quaternion for the OrientationConstraint
[in]toleranceThe absolute axes tolerances to apply to the OrientationConstraint
Returns
A full constraint message containing the orientation constraint

Definition at line 221 of file utils.cpp.

◆ constructPoseStamped()

static bool kinematic_constraints::constructPoseStamped ( XmlRpc::XmlRpcValue::iterator it,
geometry_msgs::PoseStamped &  pose 
)
static

Definition at line 278 of file utils.cpp.

◆ countIndividualConstraints()

std::size_t kinematic_constraints::countIndividualConstraints ( const moveit_msgs::Constraints &  constr)

Definition at line 124 of file utils.cpp.

◆ finishPositionConstraintDecision()

static ConstraintEvaluationResult kinematic_constraints::finishPositionConstraintDecision ( const Eigen::Vector3d pt,
const Eigen::Vector3d desired,
const std::string &  name,
double  weight,
bool  result,
bool  verbose 
)
inlinestatic

Definition at line 506 of file kinematic_constraint.cpp.

◆ isEmpty()

bool kinematic_constraints::isEmpty ( const moveit_msgs::Constraints &  constr)

Check if any constraints were specified.

Definition at line 119 of file utils.cpp.

◆ mergeConstraints()

moveit_msgs::Constraints kinematic_constraints::mergeConstraints ( const moveit_msgs::Constraints &  first,
const moveit_msgs::Constraints &  second 
)

Merge two sets of constraints into one.

This just does appending of all constraints except joint constraints. For members of type JointConstraint, the bounds specified in the parameter first take precedence over parameter second

Parameters
[in]firstThe first constraint to merge
[in]secondThe second constraint to merge
Returns
The merged set of constraints

Definition at line 50 of file utils.cpp.

◆ MOVEIT_CLASS_FORWARD() [1/6]

kinematic_constraints::MOVEIT_CLASS_FORWARD ( JointConstraint  )

◆ MOVEIT_CLASS_FORWARD() [2/6]

kinematic_constraints::MOVEIT_CLASS_FORWARD ( KinematicConstraint  )

◆ MOVEIT_CLASS_FORWARD() [3/6]

kinematic_constraints::MOVEIT_CLASS_FORWARD ( KinematicConstraintSet  )

◆ MOVEIT_CLASS_FORWARD() [4/6]

kinematic_constraints::MOVEIT_CLASS_FORWARD ( OrientationConstraint  )

◆ MOVEIT_CLASS_FORWARD() [5/6]

kinematic_constraints::MOVEIT_CLASS_FORWARD ( PositionConstraint  )

◆ MOVEIT_CLASS_FORWARD() [6/6]

kinematic_constraints::MOVEIT_CLASS_FORWARD ( VisibilityConstraint  )

◆ normalizeAbsoluteAngle()

static double kinematic_constraints::normalizeAbsoluteAngle ( const double  angle)
static

Definition at line 95 of file kinematic_constraint.cpp.

◆ normalizeAngle()

static double kinematic_constraints::normalizeAngle ( double  angle)
static

Definition at line 83 of file kinematic_constraint.cpp.

◆ resolveConstraintFrames()

bool kinematic_constraints::resolveConstraintFrames ( const moveit::core::RobotState state,
moveit_msgs::Constraints &  constraints 
)

Resolves frames used in constraints to links in the robot model.

The link_name field of a constraint is changed from the name of an object's frame or subframe to the name of the robot link that the object is attached to.

This is used in a planning request adapter which ensures that the planning problem is defined properly (the attached objects' frames are not known to the planner).

Parameters
[in]stateThe RobotState used to resolve frames.
[in]constraintsThe constraint to resolve.

Definition at line 532 of file utils.cpp.

Variable Documentation

◆ LOGNAME

const std::string kinematic_constraints::LOGNAME = "kinematic_constraint_utils"

Definition at line 48 of file utils.cpp.



moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:36