jointconfiguration.cpp
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 
18 
20 
22 {
23 
26 {}
27 
28 JointConfiguration::JointConfiguration(const std::string& group_name,
29  const std::vector<double>& config,
30  CreateJointNameFunc&& create_joint_name_func)
31  : RobotConfiguration(group_name)
32  , joints_(config)
33  , create_joint_name_func_(create_joint_name_func)
34 {}
35 
36 JointConfiguration::JointConfiguration(const std::string& group_name,
37  const std::vector<double>& config,
38  const moveit::core::RobotModelConstPtr& robot_model)
39  : RobotConfiguration(group_name, robot_model)
40  , joints_(config)
41 {
42 }
43 
44 moveit_msgs::Constraints JointConfiguration::toGoalConstraintsWithoutModel() const
45 {
47  {
48  throw JointConfigurationException("Create-Joint-Name function not set");
49  }
50 
51  moveit_msgs::Constraints gc;
52 
53  for(size_t i = 0; i < joints_.size(); ++i)
54  {
55  moveit_msgs::JointConstraint jc;
56  jc.joint_name = create_joint_name_func_(i);
57  jc.position = joints_.at(i);
58  gc.joint_constraints.push_back(jc);
59  }
60 
61  return gc;
62 }
63 
64 moveit_msgs::Constraints JointConfiguration::toGoalConstraintsWithModel() const
65 {
66  if (!robot_model_)
67  {
68  throw JointConfigurationException("No robot model set");
69  }
70 
71  robot_state::RobotState state(robot_model_);
72  state.setToDefaultValues();
73  state.setJointGroupPositions(group_name_, joints_);
74 
76  state.getRobotModel()->getJointModelGroup(group_name_));
77 }
78 
80 {
82  {
83  throw JointConfigurationException("Create-Joint-Name function not set");
84  }
85 
86  moveit_msgs::RobotState robot_state;
87  for (size_t i = 0; i < joints_.size(); ++i)
88  {
89  robot_state.joint_state.name.emplace_back( create_joint_name_func_(i) );
90  robot_state.joint_state.position.push_back(joints_.at(i));
91  }
92  return robot_state;
93 }
94 
95 robot_state::RobotState JointConfiguration::toRobotState() const
96 {
97  if (!robot_model_)
98  {
99  throw JointConfigurationException("No robot model set");
100  }
101 
102  robot_state::RobotState robot_state(robot_model_);
103  robot_state.setToDefaultValues();
104  robot_state.setJointGroupPositions(group_name_, joints_);
105  return robot_state;
106 }
107 
109 {
110  robot_state::RobotState start_state(toRobotState());
111  moveit_msgs::RobotState rob_state_msg;
112  moveit::core::robotStateToRobotStateMsg(start_state, rob_state_msg, false);
113  return rob_state_msg;
114 }
115 
116 sensor_msgs::JointState JointConfiguration::toSensorMsg() const
117 {
119  {
120  throw JointConfigurationException("Create-Joint-Name function not set");
121  }
122 
123  sensor_msgs::JointState state;
124  for (size_t i = 0; i < joints_.size(); ++i)
125  {
126  state.name.emplace_back( create_joint_name_func_(i) );
127  state.position.push_back(joints_.at(i));
128  }
129  return state;
130 }
131 
132 std::ostream& operator<< (std::ostream& os, const JointConfiguration& obj)
133 {
134  const size_t n {obj.size()};
135  os << "JointConfiguration: [";
136  for(size_t i = 0; i<n; ++i)
137  {
138  os << obj.getJoint(i);
139  if (i != n-1 )
140  {
141  os << ", ";
142  }
143  }
144  os << "]";
145 
146  return os;
147 }
148 
149 } // namespace pilz_industrial_motion_testutils
moveit_msgs::Constraints toGoalConstraintsWithoutModel() const
std::vector< double > joints_
Joint positions.
std::function< std::string(const size_t &)> CreateJointNameFunc
Class to define a robot configuration in space with the help of joint values.
moveit_msgs::RobotState toMoveitMsgsRobotStateWithoutModel() const
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)
Class to define robot configuration in space.
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
moveit_msgs::RobotState toMoveitMsgsRobotStateWithModel() const
moveit_msgs::Constraints toGoalConstraintsWithModel() const


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