38 #include <tf2_eigen/tf2_eigen.hpp>
47 const std::vector<double>& config)
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);
66 std::string msg{
"Transform of \"" };
67 msg.append(link_name).append(
"\" is unknown");
68 throw std::invalid_argument(msg);
72 geometry_msgs::msg::Pose CartesianConfiguration::toPose(
const std::vector<double>& pose)
74 geometry_msgs::msg::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::msg::PoseStamped CartesianConfiguration::toStampedPose(
const geometry_msgs::msg::Pose& pose)
88 geometry_msgs::msg::PoseStamped pose_stamped_msg;
89 pose_stamped_msg.pose = pose;
90 return pose_stamped_msg;
97 throw std::runtime_error(
"No robot model set");
110 Eigen::Isometry3d start_pose;
111 tf2::fromMsg(pose_, start_pose);
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::msg::RobotState robot_state_msg;
122 return robot_state_msg;
128 os <<
" | link name: \"" << obj.
getLinkName() <<
"\"";
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
Class to define a robot configuration in space with the help of cartesian coordinates.
bool hasSeed() const
States if a seed for the cartesian configuration is set.
const std::string & getLinkName() const
moveit_msgs::msg::RobotState toMoveitMsgsRobotState() const override
const JointConfiguration & getSeed() const
Class to define robot configuration in space.
moveit::core::RobotModelConstPtr robot_model_
std::string getGroupName() const
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)