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))
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))
57 if (robot_model && (!robot_model_->hasLinkModel(link_name_)))
59 std::string msg{
"Link \"" };
60 msg.append(link_name).append(
"\" not known to robot model");
61 throw std::invalid_argument(msg);
64 if (robot_model && (!robot_state::RobotState(robot_model_).knowsFrameTransform(link_name_)))
66 std::string msg{
"Tranform of \"" };
67 msg.append(link_name).append(
"\" is unknown");
68 throw std::invalid_argument(msg);
72 geometry_msgs::Pose CartesianConfiguration::toPose(
const std::vector<double>& pose)
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);
86 geometry_msgs::PoseStamped CartesianConfiguration::toStampedPose(
const geometry_msgs::Pose& pose)
88 geometry_msgs::PoseStamped pose_stamped_msg;
89 pose_stamped_msg.pose = pose;
90 return pose_stamped_msg;
93 moveit_msgs::RobotState CartesianConfiguration::toMoveitMsgsRobotState()
const
97 throw std::runtime_error(
"No robot model set");
100 robot_state::RobotState rstate(robot_model_);
101 rstate.setToDefaultValues();
104 rstate.setJointGroupPositions(group_name_, getSeed().getJoints());
110 Eigen::Isometry3d start_pose;
112 if (!rstate.setFromIK(rstate.getRobotModel()->getJointModelGroup(group_name_), start_pose, link_name_))
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());
120 moveit_msgs::RobotState robot_state_msg;
122 return robot_state_msg;
127 os <<
"Group name: \"" <<
obj.getGroupName() <<
"\"";
128 os <<
" | link name: \"" <<
obj.getLinkName() <<
"\"";
129 os <<
"\n" <<
obj.getPose();