jointconfiguration.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 JOINTCONFIGURATION_H
18 #define JOINTCONFIGURATION_H
19 
20 #include <string>
21 #include <vector>
22 #include <functional>
23 #include <stdexcept>
24 
25 #include <sensor_msgs/JointState.h>
28 
29 #include "robotconfiguration.h"
30 
32 {
33 class JointConfigurationException : public std::runtime_error
34 {
35 public:
36  JointConfigurationException(const std::string error_desc) : std::runtime_error(error_desc)
37  {
38  }
39 };
40 
41 using CreateJointNameFunc = std::function<std::string(const size_t&)>;
42 
48 {
49 public:
51 
52  JointConfiguration(const std::string& group_name,
53  const std::vector<double>& config,
54  CreateJointNameFunc&& create_joint_name_func);
55 
56  JointConfiguration(const std::string& group_name,
57  const std::vector<double>& config,
58  const moveit::core::RobotModelConstPtr& robot_model);
59 
60 public:
61  void setJoint(const size_t index, const double value);
62  double getJoint(const size_t index) const;
63  const std::vector<double> getJoints() const;
64 
65  size_t size() const;
66 
67  moveit_msgs::Constraints toGoalConstraints() const override;
68  moveit_msgs::RobotState toMoveitMsgsRobotState() const override;
69 
70  sensor_msgs::JointState toSensorMsg() const;
71 
72  robot_state::RobotState toRobotState() const;
73 
74  void setCreateJointNameFunc(CreateJointNameFunc create_joint_name_func);
75 
76 private:
77  moveit_msgs::RobotState toMoveitMsgsRobotStateWithoutModel() const;
78  moveit_msgs::RobotState toMoveitMsgsRobotStateWithModel() const;
79 
80  moveit_msgs::Constraints toGoalConstraintsWithoutModel() const;
81  moveit_msgs::Constraints toGoalConstraintsWithModel() const;
82 
83 private:
85  std::vector<double> joints_;
86 
88 };
89 
90 std::ostream& operator<<(std::ostream&, const JointConfiguration&);
91 
92 inline moveit_msgs::Constraints JointConfiguration::toGoalConstraints() const
93 {
94  return robot_model_ ? toGoalConstraintsWithModel() : toGoalConstraintsWithoutModel();
95 }
96 
97 inline moveit_msgs::RobotState JointConfiguration::toMoveitMsgsRobotState() const
98 {
99  return robot_model_ ? toMoveitMsgsRobotStateWithModel() : toMoveitMsgsRobotStateWithoutModel();
100 }
101 
102 inline void JointConfiguration::setJoint(const size_t index, const double value)
103 {
104  joints_.at(index) = value;
105 }
106 
107 inline double JointConfiguration::getJoint(const size_t index) const
108 {
109  return joints_.at(index);
110 }
111 
112 inline const std::vector<double> JointConfiguration::getJoints() const
113 {
114  return joints_;
115 }
116 
117 inline size_t JointConfiguration::size() const
118 {
119  return joints_.size();
120 }
121 
123 {
124  create_joint_name_func_ = create_joint_name_func;
125 }
126 
127 } // namespace pilz_industrial_motion_testutils
128 
129 #endif // JOINTCONFIGURATION_H
moveit_msgs::Constraints toGoalConstraints() const override
std::vector< double > joints_
Joint positions.
std::size_t size(custom_string const &s)
std::function< std::string(const size_t &)> CreateJointNameFunc
Class to define a robot configuration in space with the help of joint values.
void setCreateJointNameFunc(CreateJointNameFunc create_joint_name_func)
unsigned int index
void setJoint(const size_t index, const double value)
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)
Class to define robot configuration in space.
config
moveit_msgs::RobotState toMoveitMsgsRobotState() const override
int value


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