29 const std::string &link_name,
30 const std::vector<double>& config)
37 const std::string& link_name,
38 const std::vector<double>& config,
39 const moveit::core::RobotModelConstPtr& robot_model)
46 std::string msg {
"Link \""};
47 msg.append(link_name).append(
"\" not known to robot model");
48 throw std::invalid_argument(msg);
53 std::string msg {
"Tranform of \""};
54 msg.append(link_name).append(
"\" is unknown");
55 throw std::invalid_argument(msg);
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);
75 geometry_msgs::PoseStamped pose_stamped_msg;
76 pose_stamped_msg.pose = pose;
77 return pose_stamped_msg;
84 throw std::runtime_error(
"No robot model set");
88 rstate.setToDefaultValues();
94 Eigen::Affine3d start_pose;
96 if(!rstate.setFromIK(rstate.getRobotModel()->getJointModelGroup(
group_name_), start_pose,
link_name_))
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());
105 moveit_msgs::RobotState robot_state_msg;
107 return robot_state_msg;
113 os <<
" | link name: \"" << obj.
getLinkName() <<
"\"";
std::string getGroupName() const
geometry_msgs::Pose pose_
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
moveit::core::RobotModelConstPtr robot_model_
const geometry_msgs::Pose & getPose() const
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.
const JointConfiguration & getSeed() const
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
const std::string & getLinkName() const
bool hasSeed() const
States if a seed for the cartesian configuration is set.