Functions
arm_navigation_msgs Namespace Reference

Functions

void addGoalConstraintToMoveArmGoal (const arm_navigation_msgs::SimplePoseConstraint &pose_constraint, arm_navigation_msgs::MoveArmGoal &move_arm_goal)
 Add a goal constraint to the move arm action goal. More...
 
std::string armNavigationErrorCodeToString (const arm_navigation_msgs::ArmNavigationErrorCodes &error_code)
 Convert an error code into a string value. More...
 
bool constraintsToPoseStampedVector (const arm_navigation_msgs::Constraints &constraints, std::vector< geometry_msgs::PoseStamped > &poses)
 Extract pose information from a position and orientation constraint into a pose stamped message. More...
 
sensor_msgs::JointState createJointState (std::vector< std::string > joint_names, std::vector< double > joint_values)
 Create a joint state from a std vector of names and values. More...
 
void generateDisableAllowedCollisionsWithExclusions (const std::vector< std::string > &all_names, const std::vector< std::string > &exclude_names, std::vector< arm_navigation_msgs::CollisionOperation > &collision_operations)
 Generate ordered collision operates that disable all collisions in a vector of names except for a specied vector of names. More...
 
sensor_msgs::JointState jointConstraintsToJointState (const std::vector< arm_navigation_msgs::JointConstraint > &constraints)
 Extract joint position information from a set of joint constraints into a joint state message. More...
 
trajectory_msgs::JointTrajectory jointConstraintsToJointTrajectory (const std::vector< arm_navigation_msgs::JointConstraint > &constraints)
 Extract joint position information from a set of joint constraints into a joint state message. More...
 
trajectory_msgs::JointTrajectoryPoint jointStateToJointTrajectoryPoint (const sensor_msgs::JointState &state)
 Convert a joint state to a joint trajectory point message. More...
 
arm_navigation_msgs::MultiDOFJointTrajectoryPoint multiDOFJointStateToMultiDOFJointTrajectoryPoint (const arm_navigation_msgs::MultiDOFJointState &state)
 Convert a multi-dof state to a multi-dof joint trajectory point message. More...
 
arm_navigation_msgs::MultiDOFJointState poseConstraintsToMultiDOFJointState (const std::vector< arm_navigation_msgs::PositionConstraint > &position_constraints, const std::vector< arm_navigation_msgs::OrientationConstraint > &orientation_constraints)
 Extract pose information from a position and orientation constraint into a multi dof joint state. More...
 
geometry_msgs::PoseStamped poseConstraintsToPoseStamped (const arm_navigation_msgs::PositionConstraint &position_constraint, const arm_navigation_msgs::OrientationConstraint &orientation_constraint)
 Extract pose information from a position and orientation constraint into a pose stamped message. More...
 
void poseConstraintToPositionOrientationConstraints (const arm_navigation_msgs::SimplePoseConstraint &pose_constraint, arm_navigation_msgs::PositionConstraint &position_constraint, arm_navigation_msgs::OrientationConstraint &orientation_constraint)
 Convert a simple pose constraint into a position and orientation constraint. More...
 
void poseStampedToPositionOrientationConstraints (const geometry_msgs::PoseStamped &pose_stamped, const std::string &link_name, arm_navigation_msgs::PositionConstraint &position_constraint, arm_navigation_msgs::OrientationConstraint &orientation_constraint, double region_box_dimension=.01, double absolute_rpy_tolerance=.01)
 Convert a stamped pose into a position and orientation constraint. More...
 
void printJointState (const sensor_msgs::JointState &joint_state)
 Print the joint state information. More...
 
void robotStateToRobotTrajectoryPoint (const arm_navigation_msgs::RobotState &state, trajectory_msgs::JointTrajectoryPoint &point, arm_navigation_msgs::MultiDOFJointTrajectoryPoint &multi_dof_point)
 Convert a robot state to a robot trajectory message. More...
 

Function Documentation

void arm_navigation_msgs::addGoalConstraintToMoveArmGoal ( const arm_navigation_msgs::SimplePoseConstraint &  pose_constraint,
arm_navigation_msgs::MoveArmGoal &  move_arm_goal 
)

Add a goal constraint to the move arm action goal.

Parameters
Areference to a simple pose constraint.
Areference to a move arm goal message. The pose constraint will be added to the goal message as a position and orientation constraint.

Definition at line 48 of file utils.h.

std::string arm_navigation_msgs::armNavigationErrorCodeToString ( const arm_navigation_msgs::ArmNavigationErrorCodes &  error_code)
inline

Convert an error code into a string value.

Parameters
error_codeThe input error code
Returns
The resultant string message

Definition at line 254 of file convert_messages.h.

bool arm_navigation_msgs::constraintsToPoseStampedVector ( const arm_navigation_msgs::Constraints &  constraints,
std::vector< geometry_msgs::PoseStamped > &  poses 
)
inline

Extract pose information from a position and orientation constraint into a pose stamped message.

Parameters
Theinput position constraint
Theinput orientation constraint
Returns
The nominal position and orientation from the constraints are encoded into the output pose message

Definition at line 342 of file convert_messages.h.

sensor_msgs::JointState arm_navigation_msgs::createJointState ( std::vector< std::string >  joint_names,
std::vector< double >  joint_values 
)
inline

Create a joint state from a std vector of names and values.

Parameters
Theinput vector of joint names
Theinput vector of joint values
Returns
The resultant joint state

Definition at line 154 of file convert_messages.h.

void arm_navigation_msgs::generateDisableAllowedCollisionsWithExclusions ( const std::vector< std::string > &  all_names,
const std::vector< std::string > &  exclude_names,
std::vector< arm_navigation_msgs::CollisionOperation > &  collision_operations 
)
inline

Generate ordered collision operates that disable all collisions in a vector of names except for a specied vector of names.

Parameters
Allnames
Namesto exclude
Vectorfor appending collision_operations

Definition at line 64 of file utils.h.

sensor_msgs::JointState arm_navigation_msgs::jointConstraintsToJointState ( const std::vector< arm_navigation_msgs::JointConstraint > &  constraints)
inline

Extract joint position information from a set of joint constraints into a joint state message.

Parameters
Theinput vector of joint constraints
Returns
The nominal joint positions from the joint constraints are encoded into the joint state message.

Definition at line 99 of file convert_messages.h.

trajectory_msgs::JointTrajectory arm_navigation_msgs::jointConstraintsToJointTrajectory ( const std::vector< arm_navigation_msgs::JointConstraint > &  constraints)
inline

Extract joint position information from a set of joint constraints into a joint state message.

Parameters
Theinput vector of joint constraints
Returns
The nominal joint positions from the joint constraints are encoded into the joint state message.

Definition at line 117 of file convert_messages.h.

trajectory_msgs::JointTrajectoryPoint arm_navigation_msgs::jointStateToJointTrajectoryPoint ( const sensor_msgs::JointState &  state)
inline

Convert a joint state to a joint trajectory point message.

Parameters
Theinput joint state message
Returns
The output joint trajectory point message only contains position information from the joint state message.

Definition at line 60 of file convert_messages.h.

arm_navigation_msgs::MultiDOFJointTrajectoryPoint arm_navigation_msgs::multiDOFJointStateToMultiDOFJointTrajectoryPoint ( const arm_navigation_msgs::MultiDOFJointState &  state)
inline

Convert a multi-dof state to a multi-dof joint trajectory point message.

Parameters
Theinput multi-dof state
Returns
The output multi-dof joint trajectory point .

Definition at line 72 of file convert_messages.h.

arm_navigation_msgs::MultiDOFJointState arm_navigation_msgs::poseConstraintsToMultiDOFJointState ( const std::vector< arm_navigation_msgs::PositionConstraint > &  position_constraints,
const std::vector< arm_navigation_msgs::OrientationConstraint > &  orientation_constraints 
)
inline

Extract pose information from a position and orientation constraint into a multi dof joint state.

Parameters
Theinput position constraint
Theinput orientation constraint
Returns
The nominal position and orientation from the constraints are encoded into the output pose message

Definition at line 366 of file convert_messages.h.

geometry_msgs::PoseStamped arm_navigation_msgs::poseConstraintsToPoseStamped ( const arm_navigation_msgs::PositionConstraint &  position_constraint,
const arm_navigation_msgs::OrientationConstraint &  orientation_constraint 
)
inline

Extract pose information from a position and orientation constraint into a pose stamped message.

Parameters
Theinput position constraint
Theinput orientation constraint
Returns
The nominal position and orientation from the constraints are encoded into the output pose message

Definition at line 136 of file convert_messages.h.

void arm_navigation_msgs::poseConstraintToPositionOrientationConstraints ( const arm_navigation_msgs::SimplePoseConstraint &  pose_constraint,
arm_navigation_msgs::PositionConstraint &  position_constraint,
arm_navigation_msgs::OrientationConstraint &  orientation_constraint 
)
inline

Convert a simple pose constraint into a position and orientation constraint.

Parameters
Theinput pose constraint of SimplePoseConstraint form
Theoutput position constraint
Returns
The output orientation constraint

Definition at line 168 of file convert_messages.h.

void arm_navigation_msgs::poseStampedToPositionOrientationConstraints ( const geometry_msgs::PoseStamped &  pose_stamped,
const std::string &  link_name,
arm_navigation_msgs::PositionConstraint &  position_constraint,
arm_navigation_msgs::OrientationConstraint &  orientation_constraint,
double  region_box_dimension = .01,
double  absolute_rpy_tolerance = .01 
)
inline

Convert a stamped pose into a position and orientation constraint.

Parameters
Theinput pose stamped
Theoutput position constraint
(Optional)The size of constraint region cube
(Optional)The
Returns
The output orientation constraint

Definition at line 205 of file convert_messages.h.

void arm_navigation_msgs::printJointState ( const sensor_msgs::JointState &  joint_state)
inline

Print the joint state information.

Parameters
Thejoint state information to be printed

Definition at line 235 of file convert_messages.h.

void arm_navigation_msgs::robotStateToRobotTrajectoryPoint ( const arm_navigation_msgs::RobotState &  state,
trajectory_msgs::JointTrajectoryPoint &  point,
arm_navigation_msgs::MultiDOFJointTrajectoryPoint &  multi_dof_point 
)
inline

Convert a robot state to a robot trajectory message.

Parameters
Theinput robot state
Returns
The output robot trajectory point

Definition at line 85 of file convert_messages.h.



arm_navigation_msgs
Author(s): Gil Jones
autogenerated on Mon Jun 10 2019 14:26:17