Class to define a robot configuration in space with the help of cartesian coordinates.
More...
#include <cartesianconfiguration.h>
Class to define a robot configuration in space with the help of cartesian coordinates.
Definition at line 43 of file cartesianconfiguration.h.
pilz_industrial_motion_testutils::CartesianConfiguration::CartesianConfiguration |
( |
| ) |
|
pilz_industrial_motion_testutils::CartesianConfiguration::CartesianConfiguration |
( |
const std::string & |
group_name, |
|
|
const std::string & |
link_name, |
|
|
const std::vector< double > & |
config |
|
) |
| |
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 |
|
) |
| |
const boost::optional< double > pilz_industrial_motion_testutils::CartesianConfiguration::getAngleTolerance |
( |
| ) |
const |
|
inline |
const std::string & pilz_industrial_motion_testutils::CartesianConfiguration::getLinkName |
( |
| ) |
const |
|
inline |
const geometry_msgs::Pose & pilz_industrial_motion_testutils::CartesianConfiguration::getPose |
( |
| ) |
const |
|
inline |
const boost::optional< double > pilz_industrial_motion_testutils::CartesianConfiguration::getPoseTolerance |
( |
| ) |
const |
|
inline |
const JointConfiguration & pilz_industrial_motion_testutils::CartesianConfiguration::getSeed |
( |
| ) |
const |
|
inline |
bool pilz_industrial_motion_testutils::CartesianConfiguration::hasSeed |
( |
| ) |
const |
|
inline |
void pilz_industrial_motion_testutils::CartesianConfiguration::setAngleTolerance |
( |
const double |
tol | ) |
|
|
inline |
void pilz_industrial_motion_testutils::CartesianConfiguration::setLinkName |
( |
const std::string & |
link_name | ) |
|
|
inline |
void pilz_industrial_motion_testutils::CartesianConfiguration::setPose |
( |
const geometry_msgs::Pose & |
pose | ) |
|
|
inline |
void pilz_industrial_motion_testutils::CartesianConfiguration::setPoseTolerance |
( |
const double |
tol | ) |
|
|
inline |
void pilz_industrial_motion_testutils::CartesianConfiguration::setSeed |
( |
const JointConfiguration & |
config | ) |
|
|
inline |
moveit_msgs::Constraints pilz_industrial_motion_testutils::CartesianConfiguration::toGoalConstraints |
( |
| ) |
const |
|
inlineoverridevirtual |
moveit_msgs::RobotState pilz_industrial_motion_testutils::CartesianConfiguration::toMoveitMsgsRobotState |
( |
| ) |
const |
|
overridevirtual |
geometry_msgs::Pose pilz_industrial_motion_testutils::CartesianConfiguration::toPose |
( |
const std::vector< double > & |
pose | ) |
|
|
staticprivate |
geometry_msgs::PoseStamped pilz_industrial_motion_testutils::CartesianConfiguration::toStampedPose |
( |
const geometry_msgs::Pose & |
pose | ) |
|
|
staticprivate |
std::string pilz_industrial_motion_testutils::CartesianConfiguration::link_name_ |
|
private |
boost::optional<JointConfiguration> pilz_industrial_motion_testutils::CartesianConfiguration::seed_ {boost::none} |
|
private |
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 93 of file cartesianconfiguration.h.
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 89 of file cartesianconfiguration.h.
The documentation for this class was generated from the following files: