cartesianconfiguration.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTESIANCONFIGURATION_H
18 #define CARTESIANCONFIGURATION_H
19 
20 #include <vector>
21 #include <sstream>
22 
23 #include <boost/optional.hpp>
24 
26 #include <geometry_msgs/Pose.h>
27 #include <geometry_msgs/PoseStamped.h>
32 
33 #include "robotconfiguration.h"
34 #include "jointconfiguration.h"
35 
37 {
38 
44 {
45 public:
47 
48  CartesianConfiguration(const std::string& group_name,
49  const std::string& link_name,
50  const std::vector<double>& config);
51 
52  CartesianConfiguration(const std::string& group_name,
53  const std::string& link_name,
54  const std::vector<double>& config,
55  const moveit::core::RobotModelConstPtr& robot_model);
56 
57 public:
58  virtual moveit_msgs::Constraints toGoalConstraints() const override;
59  virtual moveit_msgs::RobotState toMoveitMsgsRobotState() const override;
60 
61  void setLinkName(const std::string& link_name);
62  const std::string& getLinkName() const;
63 
64  void setPose(const geometry_msgs::Pose& pose);
65  const geometry_msgs::Pose &getPose() const;
66  geometry_msgs::Pose &getPose();
67 
68  void setSeed(const JointConfiguration& config);
69  const JointConfiguration& getSeed() const;
71  bool hasSeed() const;
72 
73  void setPoseTolerance(const double tol);
74  const boost::optional<double> getPoseTolerance() const;
75 
76  void setAngleTolerance(const double tol);
77  const boost::optional<double> getAngleTolerance() const;
78 
79 private:
80  static geometry_msgs::Pose toPose(const std::vector<double>& pose);
81  static geometry_msgs::PoseStamped toStampedPose(const geometry_msgs::Pose& pose);
82 
83 private:
84  std::string link_name_;
85  geometry_msgs::Pose pose_;
86 
89  boost::optional<double> tolerance_pose_ {boost::none};
90 
93  boost::optional<double> tolerance_angle_ {boost::none};
94 
96  boost::optional<JointConfiguration> seed_ {boost::none};
97 
98 };
99 
100 std::ostream& operator<<(std::ostream&, const CartesianConfiguration&);
101 
102 inline void CartesianConfiguration::setLinkName(const std::string& link_name)
103 {
104  link_name_ = link_name;
105 }
106 
107 inline const std::string& CartesianConfiguration::getLinkName() const
108 {
109  return link_name_;
110 }
111 
112 inline void CartesianConfiguration::setPose(const geometry_msgs::Pose& pose)
113 {
114  pose_ = pose;
115 }
116 
117 inline const geometry_msgs::Pose& CartesianConfiguration::getPose() const
118 {
119  return pose_;
120 }
121 
122 inline geometry_msgs::Pose & CartesianConfiguration::getPose()
123 {
124  return pose_;
125 }
126 
127 inline moveit_msgs::Constraints CartesianConfiguration::toGoalConstraints() const
128 {
130  {
132  }
133  else
134  {
136  tolerance_pose_.value(), tolerance_angle_.value());
137  }
138 }
139 
141 {
142  seed_ = config;
143 }
144 
146 {
147  return seed_.value();
148 }
149 
151 {
152  return seed_.is_initialized();
153 }
154 
155 inline void CartesianConfiguration::setPoseTolerance(const double tol)
156 {
157  tolerance_pose_ = tol;
158 }
159 
160 inline const boost::optional<double> CartesianConfiguration::getPoseTolerance() const
161 {
162  return tolerance_pose_;
163 }
164 
165 inline void CartesianConfiguration::setAngleTolerance(const double tol)
166 {
167  tolerance_angle_ = tol;
168 }
169 
170 inline const boost::optional<double> CartesianConfiguration::getAngleTolerance() const
171 {
172  return tolerance_angle_;
173 }
174 
175 }
176 
177 #endif // CARTESIANCONFIGURATION_H
const boost::optional< double > getPoseTolerance() 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.
config
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.
Class to define a robot configuration in space with the help of cartesian coordinates.
virtual moveit_msgs::RobotState toMoveitMsgsRobotState() const override
virtual moveit_msgs::Constraints toGoalConstraints() const override
const boost::optional< double > getAngleTolerance() const
bool hasSeed() const
States if a seed for the cartesian configuration is set.


pilz_industrial_motion_testutils
Author(s):
autogenerated on Mon Apr 6 2020 03:17:28