43 #include <kdl/path_line.hpp>
44 #include <kdl/trajectory_segment.hpp>
45 #include <kdl/utilities/error.h>
47 #if __has_include(<tf2/convert.hpp>)
48 #include <tf2/convert.hpp>
50 #include <tf2/convert.h>
52 #include <rclcpp/logger.hpp>
53 #include <rclcpp/logging.hpp>
54 #include <tf2_eigen/tf2_eigen.hpp>
55 #include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
56 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
75 void TrajectoryGeneratorLIN::extractMotionPlanInfo(
const planning_scene::PlanningSceneConstPtr& scene,
79 RCLCPP_DEBUG(
getLogger(),
"Extract necessary information from motion plan request.");
85 if (!req.goal_constraints.front().joint_constraints.empty())
89 if (req.goal_constraints.front().joint_constraints.size() !=
90 robot_model_->getJointModelGroup(req.group_name)->getActiveJointModelNames().size())
92 std::ostringstream os;
93 os <<
"Number of joints in goal does not match number of joints of group "
94 "(Number joints goal: "
95 << req.goal_constraints.front().joint_constraints.size() <<
" | Number of joints of group: "
96 <<
robot_model_->getJointModelGroup(req.group_name)->getActiveJointModelNames().size() <<
')';
97 throw JointNumberMismatch(os.str());
100 for (
const auto& joint_item : req.goal_constraints.front().joint_constraints)
110 std::string frame_id;
112 info.
link_name = req.goal_constraints.front().position_constraints.front().link_name;
113 if (req.goal_constraints.front().position_constraints.front().header.frame_id.empty() ||
114 req.goal_constraints.front().orientation_constraints.front().header.frame_id.empty())
116 RCLCPP_WARN(
getLogger(),
"Frame id is not set in position/orientation constraints of "
117 "goal. Use model frame as default");
122 frame_id = req.goal_constraints.front().position_constraints.front().header.frame_id;
130 std::map<std::string, double> ik_solution;
134 std::ostringstream os;
135 os <<
"Failed to compute inverse kinematics for link: " << info.
link_name <<
" of goal pose";
136 throw LinInverseForGoalIncalculable(os.str());
145 void TrajectoryGeneratorLIN::plan(
const planning_scene::PlanningSceneConstPtr& scene,
147 double sampling_time, trajectory_msgs::msg::JointTrajectory& joint_trajectory)
150 std::unique_ptr<KDL::Path> path(setPathLIN(plan_info.start_pose, plan_info.goal_pose));
153 std::unique_ptr<KDL::VelocityProfile> vp(
160 KDL::Trajectory_Segment cart_trajectory(path.get(), vp.get(),
false);
162 moveit_msgs::msg::MoveItErrorCodes error_code;
166 plan_info.link_name, plan_info.start_joint_position, sampling_time, joint_trajectory,
169 std::ostringstream os;
170 os <<
"Failed to generate valid joint trajectory from the Cartesian path";
171 throw LinTrajectoryConversionFailure(os.str(), error_code.val);
175 std::unique_ptr<KDL::Path> TrajectoryGeneratorLIN::setPathLIN(
const Eigen::Affine3d& start_pose,
176 const Eigen::Affine3d& goal_pose)
const
178 RCLCPP_DEBUG(
getLogger(),
"Set Cartesian path for LIN command.");
180 KDL::Frame kdl_start_pose, kdl_goal_pose;
181 tf2::transformEigenToKDL(start_pose, kdl_start_pose);
182 tf2::transformEigenToKDL(goal_pose, kdl_goal_pose);
185 KDL::RotationalInterpolation* rot_interpo =
new KDL::RotationalInterpolation_SingleAxis();
187 return std::unique_ptr<KDL::Path>(
188 std::make_unique<KDL::Path_Line>(kdl_start_pose, kdl_goal_pose, rot_interpo, eqradius,
true));
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.
TrajectoryGeneratorLIN(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name)
Constructor of LIN Trajectory Generator.
This class is used to extract needed information from motion plan request.
std::map< std::string, double > goal_joint_position
Eigen::Isometry3d start_pose
Eigen::Isometry3d goal_pose
std::map< std::string, double > start_joint_position
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.