41#include <kdl/rotational_interpolation_sa.hpp>
42#include <kdl/trajectory_segment.hpp>
43#include <kdl/utilities/error.h>
44#include <kdl/utilities/utility.h>
46#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
47#include <rclcpp/logger.hpp>
48#include <rclcpp/logging.hpp>
49#include <tf2_eigen/tf2_eigen.hpp>
50#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
72 if (!(req.path_constraints.name ==
"interim" || req.path_constraints.name ==
"center"))
74 std::ostringstream os;
75 os <<
"No path constraint named \"interim\" or \"center\" found (found "
76 "unknown constraint: "
77 <<
"\"req.path_constraints.name\""
79 throw UnknownPathConstraintName(os.str());
82 if (req.path_constraints.position_constraints.size() != 1)
84 throw NoPositionConstraints(
"CIRC trajectory generator needs valid a position constraint");
87 if (req.path_constraints.position_constraints.front().constraint_region.primitive_poses.size() != 1)
89 throw NoPrimitivePose(
"CIRC trajectory generator needs valid a primitive pose");
93void TrajectoryGeneratorCIRC::extractMotionPlanInfo(
const planning_scene::PlanningSceneConstPtr& scene,
95 TrajectoryGenerator::MotionPlanInfo& info)
const
97 RCLCPP_DEBUG(
getLogger(),
"Extract necessary information from motion plan request.");
99 info.group_name = req.group_name;
103 if (!req.goal_constraints.front().joint_constraints.empty())
106 info.link_name = req.path_constraints.position_constraints.front().link_name;
109 throw UnknownLinkNameOfAuxiliaryPoint(
"Unknown link name of CIRC auxiliary point");
112 if (req.goal_constraints.front().joint_constraints.size() !=
113 robot_model_->getJointModelGroup(req.group_name)->getActiveJointModelNames().size())
115 std::ostringstream os;
116 os <<
"Number of joint constraint = " << req.goal_constraints.front().joint_constraints.size()
117 <<
" not equal to active joints of group = "
118 <<
robot_model_->getJointModelGroup(req.group_name)->getActiveJointModelNames().size();
119 throw NumberOfConstraintsMismatch(os.str());
122 for (
const auto& joint_item : req.goal_constraints.front().joint_constraints)
124 info.goal_joint_position[joint_item.joint_name] = joint_item.position;
127 computeLinkFK(robot_state, info.link_name, info.goal_joint_position, info.goal_pose);
132 std::string frame_id;
133 info.link_name = req.goal_constraints.front().position_constraints.front().link_name;
134 if (req.goal_constraints.front().position_constraints.front().header.frame_id.empty() ||
135 req.goal_constraints.front().orientation_constraints.front().header.frame_id.empty())
137 RCLCPP_WARN(
getLogger(),
"Frame id is not set in position/orientation constraints of "
138 "goal. Use model frame as default");
143 frame_id = req.goal_constraints.front().position_constraints.front().header.frame_id;
147 info.goal_pose = scene->getFrameTransform(frame_id) *
getConstraintPose(req.goal_constraints.front());
151 std::map<std::string, double> ik_solution;
152 if (!
computePoseIK(scene, info.group_name, info.link_name, info.goal_pose, frame_id, info.start_joint_position,
156 std::ostringstream os;
157 os <<
"Failed to compute inverse kinematics for link: " << info.link_name <<
" of goal pose";
158 throw CircInverseForGoalIncalculable(os.str());
164 computeLinkFK(robot_state, info.link_name, info.start_joint_position, info.start_pose);
167 std::string center_point_frame_id;
169 info.circ_path_point.first = req.path_constraints.name;
170 if (req.path_constraints.position_constraints.front().header.frame_id.empty())
172 RCLCPP_WARN(
getLogger(),
"Frame id is not set in position constraints of "
173 "path. Use model frame as default");
178 center_point_frame_id = req.path_constraints.position_constraints.front().header.frame_id;
181 Eigen::Isometry3d center_point_pose;
182 tf2::fromMsg(req.path_constraints.position_constraints.front().constraint_region.primitive_poses.front(),
185 center_point_pose = scene->getFrameTransform(center_point_frame_id) * center_point_pose;
187 if (!req.goal_constraints.front().position_constraints.empty())
189 const moveit_msgs::msg::Constraints& goal = req.goal_constraints.front();
190 geometry_msgs::msg::Point center_point = tf2::toMsg(Eigen::Vector3d(center_point_pose.translation()));
191 info.circ_path_point.second =
getConstraintPose(center_point, goal.orientation_constraints.front().orientation,
192 goal.position_constraints.front().target_point_offset)
197 info.circ_path_point.second = center_point_pose.translation();
201void TrajectoryGeneratorCIRC::plan(
const planning_scene::PlanningSceneConstPtr& scene,
203 double sampling_time, trajectory_msgs::msg::JointTrajectory& joint_trajectory)
205 std::unique_ptr<KDL::Path> cart_path(setPathCIRC(plan_info));
206 std::unique_ptr<KDL::VelocityProfile> vel_profile(
213 KDL::Trajectory_Segment cart_trajectory(cart_path.get(), vel_profile.get(),
false);
215 moveit_msgs::msg::MoveItErrorCodes error_code;
219 plan_info.link_name, plan_info.start_joint_position, sampling_time, joint_trajectory,
222 throw CircTrajectoryConversionFailure(
"Failed to generate valid joint trajectory from the Cartesian path",
227std::unique_ptr<KDL::Path> TrajectoryGeneratorCIRC::setPathCIRC(
const MotionPlanInfo& info)
const
229 RCLCPP_DEBUG(
getLogger(),
"Set Cartesian path for CIRC command.");
231 KDL::Frame start_pose, goal_pose;
232 tf2::transformEigenToKDL(info.start_pose, start_pose);
233 tf2::transformEigenToKDL(info.goal_pose, goal_pose);
235 const auto& eigen_path_point = info.circ_path_point.second;
236 const KDL::Vector path_point{ eigen_path_point.x(), eigen_path_point.y(), eigen_path_point.z() };
249 if (info.circ_path_point.first ==
"center")
258 catch (KDL::Error_MotionPlanning_Circle_No_Plane& e)
260 std::ostringstream os;
261 os <<
"Failed to create path object for circle." << e.Description();
262 throw CircleNoPlane(os.str());
264 catch (KDL::Error_MotionPlanning_Circle_ToSmall& e)
266 std::ostringstream os;
267 os <<
"Failed to create path object for circle." << e.Description();
268 throw CircleToSmall(os.str());
272 std::ostringstream os;
273 os <<
"Failed to create path object for circle." << e.
Description();
274 throw CenterPointDifferentRadius(os.str());
const char * Description() const override
Representation of a robot's state. This includes position, velocity, acceleration and effort.
This class combines CartesianLimit and JointLimits into on single class.
void printCartesianLimits() const
Prints the cartesian limits set by user. Default values for limits are 0.0.
const cartesian_limits::Params & getCartesianLimits() const
Return the cartesian limits.
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
static std::unique_ptr< KDL::Path > circleFromCenter(const KDL::Frame &start_pose, const KDL::Frame &goal_pose, const KDL::Vector ¢er_point, double eqradius)
set the path circle from start, goal and center point
static std::unique_ptr< KDL::Path > circleFromInterim(const KDL::Frame &start_pose, const KDL::Frame &goal_pose, const KDL::Vector &interim_point, double eqradius)
set circle from start, goal and interim point
TrajectoryGeneratorCIRC(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name)
Constructor of CIRC Trajectory Generator.
Base class of trajectory generators.
const moveit::core::RobotModelConstPtr robot_model_
const pilz_industrial_motion_planner::LimitsContainer planner_limits_
std::unique_ptr< KDL::VelocityProfile > cartesianTrapVelocityProfile(double max_velocity_scaling_factor, double max_acceleration_scaling_factor, const std::unique_ptr< KDL::Path > &path) const
build cartesian velocity profile for the path
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
bool computeLinkFK(moveit::core::RobotState &robot_state, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
compute the pose of a link at a given robot state
bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr &scene, const JointLimitsContainer &joint_limits, const KDL::Trajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, double sampling_time, trajectory_msgs::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
Generate joint trajectory from a KDL Cartesian trajectory.
bool computePoseIK(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const Eigen::Isometry3d &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, const double timeout=0.0)
compute the inverse kinematics of a given pose, also check robot self collision
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Eigen::Isometry3d getConstraintPose(const geometry_msgs::msg::Point &position, const geometry_msgs::msg::Quaternion &orientation, const geometry_msgs::msg::Vector3 &offset)
Adapt goal pose, defined by position+orientation, to consider offset.