17 #ifndef CARTESIANCONFIGURATION_H 18 #define CARTESIANCONFIGURATION_H 23 #include <boost/optional.hpp> 26 #include <geometry_msgs/Pose.h> 27 #include <geometry_msgs/PoseStamped.h> 49 const std::string& link_name,
50 const std::vector<double>&
config);
53 const std::string& link_name,
54 const std::vector<double>& config,
55 const moveit::core::RobotModelConstPtr& robot_model);
64 void setPose(
const geometry_msgs::Pose& pose);
65 const geometry_msgs::Pose &
getPose()
const;
80 static geometry_msgs::Pose
toPose(
const std::vector<double>& pose);
81 static geometry_msgs::PoseStamped
toStampedPose(
const geometry_msgs::Pose& pose);
96 boost::optional<JointConfiguration>
seed_ {boost::none};
147 return seed_.value();
152 return seed_.is_initialized();
177 #endif // CARTESIANCONFIGURATION_H
void setAngleTolerance(const double tol)
const boost::optional< double > getPoseTolerance() const
geometry_msgs::Pose pose_
const geometry_msgs::Pose & getPose() const
Class to define a robot configuration in space with the help of joint values.
static geometry_msgs::PoseStamped toStampedPose(const geometry_msgs::Pose &pose)
static geometry_msgs::Pose toPose(const std::vector< double > &pose)
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)
moveit_msgs::Constraints constructGoalConstraints(const robot_state::RobotState &state, const robot_model::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
boost::optional< double > tolerance_pose_
The dimensions of the sphere associated with the target region of the position constraint.
Class to define robot configuration in space.
boost::optional< JointConfiguration > seed_
The seed for computing the IK solution of the cartesian configuration.
boost::optional< double > tolerance_angle_
The value to assign to the absolute tolerances of the orientation constraint.
const JointConfiguration & getSeed() const
void setLinkName(const std::string &link_name)
Class to define a robot configuration in space with the help of cartesian coordinates.
void setPoseTolerance(const double tol)
void setPose(const geometry_msgs::Pose &pose)
virtual moveit_msgs::RobotState toMoveitMsgsRobotState() const override
void setSeed(const JointConfiguration &config)
virtual moveit_msgs::Constraints toGoalConstraints() const override
const boost::optional< double > getAngleTolerance() const
const std::string & getLinkName() const
bool hasSeed() const
States if a seed for the cartesian configuration is set.