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 {
43 {
44 public:
46 
47  CartesianConfiguration(const std::string& group_name,
48  const std::string& link_name,
49  const std::vector<double>& config);
50 
51  CartesianConfiguration(const std::string& group_name,
52  const std::string& link_name,
53  const std::vector<double>& config,
54  const moveit::core::RobotModelConstPtr& robot_model);
55 
56 public:
57  virtual moveit_msgs::Constraints toGoalConstraints() const override;
58  virtual moveit_msgs::RobotState toMoveitMsgsRobotState() const override;
59 
60  void setLinkName(const std::string& link_name);
61  const std::string& getLinkName() const;
62 
63  void setPose(const geometry_msgs::Pose& pose);
64  const geometry_msgs::Pose& getPose() const;
65  geometry_msgs::Pose& getPose();
66 
67  void setSeed(const JointConfiguration& config);
68  const JointConfiguration& getSeed() const;
70  bool hasSeed() const;
71 
72  void setPoseTolerance(const double tol);
73  const boost::optional<double> getPoseTolerance() const;
74 
75  void setAngleTolerance(const double tol);
76  const boost::optional<double> getAngleTolerance() const;
77 
78 private:
79  static geometry_msgs::Pose toPose(const std::vector<double>& pose);
80  static geometry_msgs::PoseStamped toStampedPose(const geometry_msgs::Pose& pose);
81 
82 private:
83  std::string link_name_;
84  geometry_msgs::Pose pose_;
85 
88  boost::optional<double> tolerance_pose_{ boost::none };
89 
92  boost::optional<double> tolerance_angle_{ boost::none };
93 
95  boost::optional<JointConfiguration> seed_{ boost::none };
96 };
97 
98 std::ostream& operator<<(std::ostream&, const CartesianConfiguration&);
99 
100 inline void CartesianConfiguration::setLinkName(const std::string& link_name)
101 {
102  link_name_ = link_name;
103 }
104 
105 inline const std::string& CartesianConfiguration::getLinkName() const
106 {
107  return link_name_;
108 }
109 
110 inline void CartesianConfiguration::setPose(const geometry_msgs::Pose& pose)
111 {
112  pose_ = pose;
113 }
114 
115 inline const geometry_msgs::Pose& CartesianConfiguration::getPose() const
116 {
117  return pose_;
118 }
119 
120 inline geometry_msgs::Pose& CartesianConfiguration::getPose()
121 {
122  return pose_;
123 }
124 
125 inline moveit_msgs::Constraints CartesianConfiguration::toGoalConstraints() const
126 {
128  {
130  }
131  else
132  {
135  }
136 }
137 
139 {
140  seed_ = config;
141 }
142 
144 {
145  return seed_.value();
146 }
147 
149 {
150  return seed_.is_initialized();
151 }
152 
153 inline void CartesianConfiguration::setPoseTolerance(const double tol)
154 {
155  tolerance_pose_ = tol;
156 }
157 
158 inline const boost::optional<double> CartesianConfiguration::getPoseTolerance() const
159 {
160  return tolerance_pose_;
161 }
162 
163 inline void CartesianConfiguration::setAngleTolerance(const double tol)
164 {
165  tolerance_angle_ = tol;
166 }
167 
168 inline const boost::optional<double> CartesianConfiguration::getAngleTolerance() const
169 {
170  return tolerance_angle_;
171 }
172 
173 } // namespace pilz_industrial_motion_testutils
174 
175 #endif // CARTESIANCONFIGURATION_H
const boost::optional< double > getAngleTolerance() 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.
bool hasSeed() const
States if a seed for the cartesian configuration is set.
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 > getPoseTolerance() const


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