cartesianconfiguration.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 
19 #include <stdexcept>
20 
22 {
23 
26 {}
27 
28 CartesianConfiguration::CartesianConfiguration(const std::string& group_name,
29  const std::string &link_name,
30  const std::vector<double>& config)
31  : RobotConfiguration(group_name)
32  , link_name_(link_name)
33  , pose_(toPose(config))
34 {}
35 
36 CartesianConfiguration::CartesianConfiguration(const std::string& group_name,
37  const std::string& link_name,
38  const std::vector<double>& config,
39  const moveit::core::RobotModelConstPtr& robot_model)
40  : RobotConfiguration(group_name, robot_model)
41  , link_name_(link_name)
42  , pose_(toPose(config))
43 {
44  if (robot_model && (!robot_model_->hasLinkModel(link_name_)))
45  {
46  std::string msg {"Link \""};
47  msg.append(link_name).append("\" not known to robot model");
48  throw std::invalid_argument(msg);
49  }
50 
51  if (robot_model && (!robot_state::RobotState(robot_model_).knowsFrameTransform(link_name_)))
52  {
53  std::string msg {"Tranform of \""};
54  msg.append(link_name).append("\" is unknown");
55  throw std::invalid_argument(msg);
56  }
57 }
58 
59 geometry_msgs::Pose CartesianConfiguration::toPose(const std::vector<double>& pose)
60 {
61  geometry_msgs::Pose pose_msg;
62  pose_msg.position.x = pose.at(0);
63  pose_msg.position.y = pose.at(1);
64  pose_msg.position.z = pose.at(2);
65  pose_msg.orientation.x = pose.at(3);
66  pose_msg.orientation.y = pose.at(4);
67  pose_msg.orientation.z = pose.at(5);
68  pose_msg.orientation.w = pose.at(6);
69 
70  return pose_msg;
71 }
72 
73 geometry_msgs::PoseStamped CartesianConfiguration::toStampedPose(const geometry_msgs::Pose& pose)
74 {
75  geometry_msgs::PoseStamped pose_stamped_msg;
76  pose_stamped_msg.pose = pose;
77  return pose_stamped_msg;
78 }
79 
80 moveit_msgs::RobotState CartesianConfiguration::toMoveitMsgsRobotState() const
81 {
82  if (!robot_model_)
83  {
84  throw std::runtime_error("No robot model set");
85  }
86 
87  robot_state::RobotState rstate(robot_model_);
88  rstate.setToDefaultValues();
89  if (hasSeed()){ rstate.setJointGroupPositions(group_name_, getSeed().getJoints()); }
90 
91  rstate.update();
92 
93  // set to Cartesian pose
94  Eigen::Affine3d start_pose;
95  tf::poseMsgToEigen(pose_, start_pose);
96  if(!rstate.setFromIK(rstate.getRobotModel()->getJointModelGroup(group_name_), start_pose, link_name_))
97  {
98  std::ostringstream os;
99  os << "No solution for ik \n" << start_pose.translation() << "\n"
100  << start_pose.linear();
101  throw std::runtime_error(os.str());
102  }
103 
104  // Conversion to RobotState msg type
105  moveit_msgs::RobotState robot_state_msg;
106  moveit::core::robotStateToRobotStateMsg(rstate, robot_state_msg, true);
107  return robot_state_msg;
108 }
109 
110 std::ostream& operator<< (std::ostream& os, const CartesianConfiguration& obj)
111 {
112  os << "Group name: \"" << obj.getGroupName() << "\"";
113  os << " | link name: \"" << obj.getLinkName() << "\"";
114  os << "\n" << obj.getPose();
115  return os;
116 }
117 
118 } // namespace pilz_industrial_motion_testutils
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
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 &)
Class to define robot configuration in space.
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
Class to define a robot configuration in space with the help of cartesian coordinates.
virtual moveit_msgs::RobotState toMoveitMsgsRobotState() const override
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