Public Member Functions | Static Private Member Functions | Private Attributes | List of all members
pilz_industrial_motion_testutils::CartesianConfiguration Class Reference

Class to define a robot configuration in space with the help of cartesian coordinates. More...

#include <cartesianconfiguration.h>

Inheritance diagram for pilz_industrial_motion_testutils::CartesianConfiguration:
Inheritance graph
[legend]

Public Member Functions

 CartesianConfiguration ()
 
 CartesianConfiguration (const std::string &group_name, const std::string &link_name, const std::vector< double > &config)
 
 CartesianConfiguration (const std::string &group_name, const std::string &link_name, const std::vector< double > &config, const moveit::core::RobotModelConstPtr &robot_model)
 
const boost::optional< double > getAngleTolerance () const
 
const std::string & getLinkName () const
 
const geometry_msgs::PosegetPose () const
 
geometry_msgs::PosegetPose ()
 
const boost::optional< double > getPoseTolerance () const
 
const JointConfigurationgetSeed () const
 
bool hasSeed () const
 States if a seed for the cartesian configuration is set. More...
 
void setAngleTolerance (const double tol)
 
void setLinkName (const std::string &link_name)
 
void setPose (const geometry_msgs::Pose &pose)
 
void setPoseTolerance (const double tol)
 
void setSeed (const JointConfiguration &config)
 
virtual moveit_msgs::Constraints toGoalConstraints () const override
 
virtual moveit_msgs::RobotState toMoveitMsgsRobotState () const override
 
- Public Member Functions inherited from pilz_industrial_motion_testutils::RobotConfiguration
void clearModel ()
 
std::string getGroupName () const
 
 RobotConfiguration ()
 
 RobotConfiguration (const std::string &group_name)
 
 RobotConfiguration (const std::string &group_name, const moveit::core::RobotModelConstPtr &robot_model)
 
void setGroupName (const std::string &group_name)
 
void setRobotModel (moveit::core::RobotModelConstPtr robot_model)
 

Static Private Member Functions

static geometry_msgs::Pose toPose (const std::vector< double > &pose)
 
static geometry_msgs::PoseStamped toStampedPose (const geometry_msgs::Pose &pose)
 

Private Attributes

std::string link_name_
 
geometry_msgs::Pose pose_
 
boost::optional< JointConfigurationseed_ { boost::none }
 The seed for computing the IK solution of the cartesian configuration. More...
 
boost::optional< double > tolerance_angle_ { boost::none }
 The value to assign to the absolute tolerances of the orientation constraint. More...
 
boost::optional< double > tolerance_pose_ { boost::none }
 The dimensions of the sphere associated with the target region of the position constraint. More...
 

Additional Inherited Members

- Protected Attributes inherited from pilz_industrial_motion_testutils::RobotConfiguration
std::string group_name_
 
moveit::core::RobotModelConstPtr robot_model_
 

Detailed Description

Class to define a robot configuration in space with the help of cartesian coordinates.

Definition at line 42 of file cartesianconfiguration.h.

Constructor & Destructor Documentation

◆ CartesianConfiguration() [1/3]

pilz_industrial_motion_testutils::CartesianConfiguration::CartesianConfiguration ( )

Definition at line 23 of file cartesianconfiguration.cpp.

◆ CartesianConfiguration() [2/3]

pilz_industrial_motion_testutils::CartesianConfiguration::CartesianConfiguration ( const std::string &  group_name,
const std::string &  link_name,
const std::vector< double > &  config 
)

Definition at line 27 of file cartesianconfiguration.cpp.

◆ CartesianConfiguration() [3/3]

pilz_industrial_motion_testutils::CartesianConfiguration::CartesianConfiguration ( const std::string &  group_name,
const std::string &  link_name,
const std::vector< double > &  config,
const moveit::core::RobotModelConstPtr &  robot_model 
)

Definition at line 34 of file cartesianconfiguration.cpp.

Member Function Documentation

◆ getAngleTolerance()

const boost::optional< double > pilz_industrial_motion_testutils::CartesianConfiguration::getAngleTolerance ( ) const
inline

Definition at line 168 of file cartesianconfiguration.h.

◆ getLinkName()

const std::string & pilz_industrial_motion_testutils::CartesianConfiguration::getLinkName ( ) const
inline

Definition at line 105 of file cartesianconfiguration.h.

◆ getPose() [1/2]

const geometry_msgs::Pose & pilz_industrial_motion_testutils::CartesianConfiguration::getPose ( ) const
inline

Definition at line 115 of file cartesianconfiguration.h.

◆ getPose() [2/2]

geometry_msgs::Pose & pilz_industrial_motion_testutils::CartesianConfiguration::getPose ( )
inline

Definition at line 120 of file cartesianconfiguration.h.

◆ getPoseTolerance()

const boost::optional< double > pilz_industrial_motion_testutils::CartesianConfiguration::getPoseTolerance ( ) const
inline

Definition at line 158 of file cartesianconfiguration.h.

◆ getSeed()

const JointConfiguration & pilz_industrial_motion_testutils::CartesianConfiguration::getSeed ( ) const
inline

Definition at line 143 of file cartesianconfiguration.h.

◆ hasSeed()

bool pilz_industrial_motion_testutils::CartesianConfiguration::hasSeed ( ) const
inline

States if a seed for the cartesian configuration is set.

Definition at line 148 of file cartesianconfiguration.h.

◆ setAngleTolerance()

void pilz_industrial_motion_testutils::CartesianConfiguration::setAngleTolerance ( const double  tol)
inline

Definition at line 163 of file cartesianconfiguration.h.

◆ setLinkName()

void pilz_industrial_motion_testutils::CartesianConfiguration::setLinkName ( const std::string &  link_name)
inline

Definition at line 100 of file cartesianconfiguration.h.

◆ setPose()

void pilz_industrial_motion_testutils::CartesianConfiguration::setPose ( const geometry_msgs::Pose pose)
inline

Definition at line 110 of file cartesianconfiguration.h.

◆ setPoseTolerance()

void pilz_industrial_motion_testutils::CartesianConfiguration::setPoseTolerance ( const double  tol)
inline

Definition at line 153 of file cartesianconfiguration.h.

◆ setSeed()

void pilz_industrial_motion_testutils::CartesianConfiguration::setSeed ( const JointConfiguration config)
inline

Definition at line 138 of file cartesianconfiguration.h.

◆ toGoalConstraints()

moveit_msgs::Constraints pilz_industrial_motion_testutils::CartesianConfiguration::toGoalConstraints ( ) const
inlineoverridevirtual

◆ toMoveitMsgsRobotState()

moveit_msgs::RobotState pilz_industrial_motion_testutils::CartesianConfiguration::toMoveitMsgsRobotState ( ) const
overridevirtual

◆ toPose()

geometry_msgs::Pose pilz_industrial_motion_testutils::CartesianConfiguration::toPose ( const std::vector< double > &  pose)
staticprivate

Definition at line 55 of file cartesianconfiguration.cpp.

◆ toStampedPose()

geometry_msgs::PoseStamped pilz_industrial_motion_testutils::CartesianConfiguration::toStampedPose ( const geometry_msgs::Pose pose)
staticprivate

Definition at line 69 of file cartesianconfiguration.cpp.

Member Data Documentation

◆ link_name_

std::string pilz_industrial_motion_testutils::CartesianConfiguration::link_name_
private

Definition at line 83 of file cartesianconfiguration.h.

◆ pose_

geometry_msgs::Pose pilz_industrial_motion_testutils::CartesianConfiguration::pose_
private

Definition at line 84 of file cartesianconfiguration.h.

◆ seed_

boost::optional<JointConfiguration> pilz_industrial_motion_testutils::CartesianConfiguration::seed_ { boost::none }
private

The seed for computing the IK solution of the cartesian configuration.

Definition at line 95 of file cartesianconfiguration.h.

◆ tolerance_angle_

boost::optional<double> pilz_industrial_motion_testutils::CartesianConfiguration::tolerance_angle_ { boost::none }
private

The value to assign to the absolute tolerances of the orientation constraint.

Definition at line 92 of file cartesianconfiguration.h.

◆ tolerance_pose_

boost::optional<double> pilz_industrial_motion_testutils::CartesianConfiguration::tolerance_pose_ { boost::none }
private

The dimensions of the sphere associated with the target region of the position constraint.

Definition at line 88 of file cartesianconfiguration.h.


The documentation for this class was generated from the following files:


pilz_industrial_motion_testutils
Author(s):
autogenerated on Mon Feb 28 2022 23:13:36