cartesianconfiguration.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019 Pilz GmbH & Co. KG
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 #include <stdexcept>
38 #include <tf2_eigen/tf2_eigen.h>
39 
41 {
43 {
44 }
45 
46 CartesianConfiguration::CartesianConfiguration(const std::string& group_name, const std::string& link_name,
47  const std::vector<double>& config)
48  : RobotConfiguration(group_name), link_name_(link_name), pose_(toPose(config))
49 {
50 }
51 
52 CartesianConfiguration::CartesianConfiguration(const std::string& group_name, const std::string& link_name,
53  const std::vector<double>& config,
54  const moveit::core::RobotModelConstPtr& robot_model)
55  : RobotConfiguration(group_name, robot_model), link_name_(link_name), pose_(toPose(config))
56 {
57  if (robot_model && (!robot_model_->hasLinkModel(link_name_)))
58  {
59  std::string msg{ "Link \"" };
60  msg.append(link_name).append("\" not known to robot model");
61  throw std::invalid_argument(msg);
62  }
63 
64  if (robot_model && (!robot_state::RobotState(robot_model_).knowsFrameTransform(link_name_)))
65  {
66  std::string msg{ "Tranform of \"" };
67  msg.append(link_name).append("\" is unknown");
68  throw std::invalid_argument(msg);
69  }
70 }
71 
72 geometry_msgs::Pose CartesianConfiguration::toPose(const std::vector<double>& pose)
73 {
74  geometry_msgs::Pose pose_msg;
75  pose_msg.position.x = pose.at(0);
76  pose_msg.position.y = pose.at(1);
77  pose_msg.position.z = pose.at(2);
78  pose_msg.orientation.x = pose.at(3);
79  pose_msg.orientation.y = pose.at(4);
80  pose_msg.orientation.z = pose.at(5);
81  pose_msg.orientation.w = pose.at(6);
82 
83  return pose_msg;
84 }
85 
86 geometry_msgs::PoseStamped CartesianConfiguration::toStampedPose(const geometry_msgs::Pose& pose)
87 {
88  geometry_msgs::PoseStamped pose_stamped_msg;
89  pose_stamped_msg.pose = pose;
90  return pose_stamped_msg;
91 }
92 
93 moveit_msgs::RobotState CartesianConfiguration::toMoveitMsgsRobotState() const
94 {
95  if (!robot_model_)
96  {
97  throw std::runtime_error("No robot model set");
98  }
99 
100  robot_state::RobotState rstate(robot_model_);
101  rstate.setToDefaultValues();
102  if (hasSeed())
103  {
104  rstate.setJointGroupPositions(group_name_, getSeed().getJoints());
105  }
106 
107  rstate.update();
108 
109  // set to Cartesian pose
110  Eigen::Isometry3d start_pose;
111  tf2::fromMsg(pose_, start_pose);
112  if (!rstate.setFromIK(rstate.getRobotModel()->getJointModelGroup(group_name_), start_pose, link_name_))
113  {
114  std::ostringstream os;
115  os << "No solution for ik \n" << start_pose.translation() << "\n" << start_pose.linear();
116  throw std::runtime_error(os.str());
117  }
118 
119  // Conversion to RobotState msg type
120  moveit_msgs::RobotState robot_state_msg;
121  moveit::core::robotStateToRobotStateMsg(rstate, robot_state_msg, true);
122  return robot_state_msg;
123 }
124 
125 std::ostream& operator<<(std::ostream& os, const CartesianConfiguration& obj)
126 {
127  os << "Group name: \"" << obj.getGroupName() << "\"";
128  os << " | link name: \"" << obj.getLinkName() << "\"";
129  os << "\n" << obj.getPose();
130  return os;
131 }
132 
133 } // namespace pilz_industrial_motion_planner_testutils
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
cartesianconfiguration.h
obj
CollisionObject< S > * obj
pilz_industrial_motion_planner_testutils
Definition: basecmd.h:42
pilz_industrial_motion_planner_testutils::operator<<
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)
Definition: cartesianconfiguration.cpp:157
pose_
const geometry_msgs::Pose * pose_
pilz_industrial_motion_planner_testutils::CartesianConfiguration::CartesianConfiguration
CartesianConfiguration()
Definition: cartesianconfiguration.cpp:74
pilz_industrial_motion_planner_testutils::CartesianConfiguration
Class to define a robot configuration in space with the help of cartesian coordinates.
Definition: cartesianconfiguration.h:90
config
config
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)


pilz_industrial_motion_planner_testutils
Author(s):
autogenerated on Sat May 3 2025 02:28:27