38 #include <tf2/LinearMath/Quaternion.h>
39 #include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
40 #include <tf2_eigen/tf2_eigen.hpp>
41 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
53 const std::string& group_name,
const std::string& link_name,
54 const Eigen::Isometry3d& pose,
const std::string& frame_id,
55 const std::map<std::string, double>& seed,
56 std::map<std::string, double>& solution,
bool check_self_collision,
59 const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel();
60 if (!robot_model->hasJointModelGroup(group_name))
62 RCLCPP_ERROR_STREAM(
getLogger(),
"Robot model has no planning group named as " << group_name);
66 if (frame_id != robot_model->getModelFrame())
68 RCLCPP_ERROR_STREAM(
getLogger(),
"Given frame (" << frame_id <<
") is unequal to model frame("
69 << robot_model->getModelFrame() <<
')');
77 if (check_self_collision)
81 const double* joint_group_variable_values) {
83 joint_group_variable_values);
89 if (rstate.setFromIK(jmg, pose, link_name, timeout, ik_constraint_function))
94 solution[joint_name] = rstate.getVariablePosition(joint_name);
100 RCLCPP_ERROR(
getLogger(),
"Unable to find IK solution.");
108 const std::string& group_name,
const std::string& link_name,
109 const geometry_msgs::msg::Pose& pose,
const std::string& frame_id,
110 const std::map<std::string, double>& seed,
111 std::map<std::string, double>& solution,
bool check_self_collision,
112 const double timeout)
114 Eigen::Isometry3d pose_eigen;
115 tf2::convert<geometry_msgs::msg::Pose, Eigen::Isometry3d>(pose, pose_eigen);
116 return computePoseIK(scene, group_name, link_name, pose_eigen, frame_id, seed, solution, check_self_collision,
121 const std::map<std::string, double>& joint_state,
122 Eigen::Isometry3d& pose)
127 RCLCPP_ERROR_STREAM(
getLogger(),
"The target link " << link_name <<
" is not known by robot.");
141 const std::map<std::string, double>& position_last,
const std::map<std::string, double>& velocity_last,
142 const std::map<std::string, double>& position_current,
double duration_last,
double duration_current,
145 const double epsilon = 10e-6;
146 if (duration_current <= epsilon)
148 RCLCPP_ERROR(
getLogger(),
"Sample duration too small, cannot compute the velocity");
152 double velocity_current, acceleration_current;
154 for (
const auto& pos : position_current)
156 velocity_current = (pos.second - position_last.at(pos.first)) / duration_current;
158 if (!
joint_limits.verifyVelocityLimit(pos.first, velocity_current))
160 RCLCPP_ERROR_STREAM(
getLogger(),
"Joint velocity limit of "
161 << pos.first <<
" violated. Set the velocity scaling factor lower!"
162 <<
" Actual joint velocity is " << velocity_current
163 <<
", while the limit is " <<
joint_limits.getLimit(pos.first).max_velocity
168 acceleration_current = (velocity_current - velocity_last.at(pos.first)) / (duration_last + duration_current) * 2;
170 if (fabs(velocity_last.at(pos.first)) <= fabs(velocity_current))
172 if (!
joint_limits.verifyAccelerationLimit(pos.first, acceleration_current))
174 RCLCPP_ERROR_STREAM(
getLogger(),
"Joint acceleration limit of "
175 << pos.first <<
" violated. Set the acceleration scaling factor lower!"
176 <<
" Actual joint acceleration is " << acceleration_current
177 <<
", while the limit is "
178 <<
joint_limits.getLimit(pos.first).max_acceleration <<
". ");
185 if (!
joint_limits.verifyDecelerationLimit(pos.first, acceleration_current))
187 RCLCPP_ERROR_STREAM(
getLogger(),
"Joint deceleration limit of "
188 << pos.first <<
" violated. Set the acceleration scaling factor lower!"
189 <<
" Actual joint deceleration is " << acceleration_current
190 <<
", while the limit is "
191 <<
joint_limits.getLimit(pos.first).max_deceleration <<
". ");
201 const planning_scene::PlanningSceneConstPtr& scene,
203 const std::string& group_name,
const std::string& link_name,
204 const std::map<std::string, double>& initial_joint_position,
double sampling_time,
205 trajectory_msgs::msg::JointTrajectory& joint_trajectory, moveit_msgs::msg::MoveItErrorCodes& error_code,
206 bool check_self_collision)
208 RCLCPP_DEBUG(
getLogger(),
"Generate joint trajectory from a Cartesian trajectory.");
210 const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel();
212 rclcpp::Time generation_begin = clock.now();
215 const double epsilon = 10e-06;
216 std::vector<double> time_samples;
217 for (
double t_sample = 0.0; t_sample < trajectory.Duration() - epsilon; t_sample += sampling_time)
219 time_samples.push_back(t_sample);
221 time_samples.push_back(trajectory.Duration());
224 Eigen::Isometry3d pose_sample;
225 std::map<std::string, double> ik_solution_last, ik_solution, joint_velocity_last;
226 ik_solution_last = initial_joint_position;
227 for (
const auto& item : ik_solution_last)
229 joint_velocity_last[item.first] = 0.0;
232 for (std::vector<double>::const_iterator time_iter = time_samples.begin(); time_iter != time_samples.end();
235 tf2::transformKDLToEigen(trajectory.Pos(*time_iter), pose_sample);
237 if (!
computePoseIK(scene, group_name, link_name, pose_sample, robot_model->getModelFrame(), ik_solution_last,
238 ik_solution, check_self_collision))
240 RCLCPP_ERROR(
getLogger(),
"Failed to compute inverse kinematics solution for sampled Cartesian pose.");
241 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
242 joint_trajectory.points.clear();
247 double duration_current_sample = sampling_time;
249 if (time_iter == (time_samples.end() - 1) && time_samples.size() > 1)
251 duration_current_sample = *time_iter - *(time_iter - 1);
253 if (time_samples.size() == 1)
255 duration_current_sample = *time_iter;
259 if (time_iter != time_samples.begin() &&
263 RCLCPP_ERROR_STREAM(
getLogger(),
"Inverse kinematics solution at "
265 <<
"s violates the joint velocity/acceleration/deceleration limits.");
266 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
267 joint_trajectory.points.clear();
272 trajectory_msgs::msg::JointTrajectoryPoint point;
275 joint_trajectory.joint_names.clear();
276 for (
const auto& start_joint : initial_joint_position)
278 joint_trajectory.joint_names.push_back(start_joint.first);
281 point.time_from_start = rclcpp::Duration::from_seconds(*time_iter);
282 for (
const auto& joint_name : joint_trajectory.joint_names)
284 point.positions.push_back(ik_solution.at(joint_name));
286 if (time_iter != time_samples.begin() && time_iter != time_samples.end() - 1)
288 double joint_velocity =
289 (ik_solution.at(joint_name) - ik_solution_last.at(joint_name)) / duration_current_sample;
290 point.velocities.push_back(joint_velocity);
291 point.accelerations.push_back((joint_velocity - joint_velocity_last.at(joint_name)) /
292 (duration_current_sample + sampling_time) * 2);
293 joint_velocity_last[joint_name] = joint_velocity;
297 point.velocities.push_back(0.);
298 point.accelerations.push_back(0.);
299 joint_velocity_last[joint_name] = 0.;
304 joint_trajectory.points.push_back(point);
305 ik_solution_last = ik_solution;
308 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
309 double duration_ms = (clock.now() - generation_begin).seconds() * 1000;
310 RCLCPP_DEBUG_STREAM(
getLogger(),
"Generate trajectory (N-Points: "
311 << joint_trajectory.points.size() <<
") took " << duration_ms <<
" ms | "
312 << duration_ms / joint_trajectory.points.size() <<
" ms per Point");
318 const planning_scene::PlanningSceneConstPtr& scene,
321 const std::string& link_name,
const std::map<std::string, double>& initial_joint_position,
322 const std::map<std::string, double>& initial_joint_velocity,
323 trajectory_msgs::msg::JointTrajectory& joint_trajectory, moveit_msgs::msg::MoveItErrorCodes& error_code,
324 bool check_self_collision)
326 RCLCPP_DEBUG(
getLogger(),
"Generate joint trajectory from a Cartesian trajectory.");
328 const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel();
330 rclcpp::Time generation_begin = clock.now();
332 std::map<std::string, double> ik_solution_last = initial_joint_position;
333 std::map<std::string, double> joint_velocity_last = initial_joint_velocity;
334 double duration_last = 0;
335 double duration_current = 0;
336 joint_trajectory.joint_names.clear();
337 for (
const auto& joint_position : ik_solution_last)
339 joint_trajectory.joint_names.push_back(joint_position.first);
341 std::map<std::string, double> ik_solution;
342 for (
size_t i = 0; i < trajectory.
points.size(); ++i)
345 if (!
computePoseIK(scene, group_name, link_name, trajectory.
points.at(i).pose, robot_model->getModelFrame(),
346 ik_solution_last, ik_solution, check_self_collision))
348 RCLCPP_ERROR(
getLogger(),
"Failed to compute inverse kinematics solution for sampled "
350 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
351 joint_trajectory.points.clear();
358 duration_current = trajectory.
points.front().time_from_start.seconds();
359 duration_last = duration_current;
364 trajectory.
points.at(i).time_from_start.seconds() - trajectory.
points.at(i - 1).time_from_start.seconds();
367 if (!
verifySampleJointLimits(ik_solution_last, joint_velocity_last, ik_solution, duration_last, duration_current,
374 RCLCPP_ERROR_STREAM(
getLogger(),
"Inverse kinematics solution of the "
376 <<
"th sample violates the joint "
377 "velocity/acceleration/deceleration limits.");
378 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
379 joint_trajectory.points.clear();
385 trajectory_msgs::msg::JointTrajectoryPoint waypoint_joint;
386 waypoint_joint.time_from_start = trajectory.
points.at(i).time_from_start;
387 for (
const auto& joint_name : joint_trajectory.joint_names)
389 waypoint_joint.positions.push_back(ik_solution.at(joint_name));
390 double joint_velocity = (ik_solution.at(joint_name) - ik_solution_last.at(joint_name)) / duration_current;
391 waypoint_joint.velocities.push_back(joint_velocity);
392 waypoint_joint.accelerations.push_back((joint_velocity - joint_velocity_last.at(joint_name)) /
393 (duration_current + duration_last) * 2);
395 joint_velocity_last[joint_name] = joint_velocity;
399 joint_trajectory.points.push_back(waypoint_joint);
400 ik_solution_last = ik_solution;
401 duration_last = duration_current;
404 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
406 double duration_ms = (clock.now() - generation_begin).seconds() * 1000;
407 RCLCPP_DEBUG_STREAM(
getLogger(),
"Generate trajectory (N-Points: "
408 << joint_trajectory.points.size() <<
") took " << duration_ms <<
" ms | "
409 << duration_ms / joint_trajectory.points.size() <<
" ms per Point");
415 const robot_trajectory::RobotTrajectoryPtr& first_trajectory,
416 const robot_trajectory::RobotTrajectoryPtr& second_trajectory,
double epsilon,
double& sampling_time)
420 std::size_t n1 = first_trajectory->getWayPointCount() - 1;
421 std::size_t n2 = second_trajectory->getWayPointCount() - 1;
422 if ((n1 < 2) && (n2 < 2))
424 RCLCPP_ERROR_STREAM(
getLogger(),
"Both trajectories do not have enough points to determine sampling time.");
430 sampling_time = first_trajectory->getWayPointDurationFromPrevious(1);
434 sampling_time = second_trajectory->getWayPointDurationFromPrevious(1);
437 for (std::size_t i = 1; i < std::max(n1, n2); ++i)
441 if (fabs(sampling_time - first_trajectory->getWayPointDurationFromPrevious(i)) > epsilon)
443 RCLCPP_ERROR_STREAM(
getLogger(),
"First trajectory violates sampline time "
444 << sampling_time <<
" between points " << (i - 1) <<
"and " << i
452 if (fabs(sampling_time - second_trajectory->getWayPointDurationFromPrevious(i)) > epsilon)
454 RCLCPP_ERROR_STREAM(
getLogger(),
"Second trajectory violates sampline time "
455 << sampling_time <<
" between points " << (i - 1) <<
"and " << i
467 const std::string& joint_group_name,
double epsilon)
469 Eigen::VectorXd joint_position_1, joint_position_2;
474 if ((joint_position_1 - joint_position_2).norm() > epsilon)
476 RCLCPP_DEBUG_STREAM(
getLogger(),
"Joint positions of the two states are different. state1: "
477 << joint_position_1 <<
" state2: " << joint_position_2);
481 Eigen::VectorXd joint_velocity_1, joint_velocity_2;
486 if ((joint_velocity_1 - joint_velocity_2).norm() > epsilon)
488 RCLCPP_DEBUG_STREAM(
getLogger(),
"Joint velocities of the two states are different. state1: "
489 << joint_velocity_1 <<
" state2: " << joint_velocity_2);
493 Eigen::VectorXd joint_acc_1, joint_acc_2;
498 if ((joint_acc_1 - joint_acc_2).norm() > epsilon)
500 RCLCPP_DEBUG_STREAM(
getLogger(),
"Joint accelerations of the two states are different. state1: "
501 << joint_acc_1 <<
" state2: " << joint_acc_2);
509 const std::string& group,
double EPSILON)
511 Eigen::VectorXd joint_variable;
513 if (joint_variable.norm() >
EPSILON)
515 RCLCPP_DEBUG(
getLogger(),
"Joint velocities are not zero.");
519 if (joint_variable.norm() >
EPSILON)
521 RCLCPP_DEBUG(
getLogger(),
"Joint accelerations are not zero.");
529 const robot_trajectory::RobotTrajectoryPtr& traj,
530 bool inverseOrder, std::size_t& index)
532 RCLCPP_DEBUG(
getLogger(),
"Start linear search for intersection point.");
534 const size_t waypoint_num = traj->getWayPointCount();
538 for (
size_t i = waypoint_num - 1; i > 0; --i)
540 if (
intersectionFound(center_position, traj->getWayPointPtr(i)->getFrameTransform(link_name).translation(),
541 traj->getWayPointPtr(i - 1)->getFrameTransform(link_name).translation(), r))
550 for (
size_t i = 0; i < waypoint_num - 1; ++i)
552 if (
intersectionFound(center_position, traj->getWayPointPtr(i)->getFrameTransform(link_name).translation(),
553 traj->getWayPointPtr(i + 1)->getFrameTransform(link_name).translation(), r))
568 return ((p_current - p_center).norm() <= r) && ((p_next - p_center).norm() >= r);
574 const double*
const ik_solution)
582 scene->checkSelfCollision(collision_req, collision_res, *rstate);
589 tf2::convert<geometry_msgs::msg::Quaternion, tf2::Quaternion>(quat, q);
590 quat = tf2::toMsg(q.normalized());
594 const geometry_msgs::msg::Quaternion& orientation,
595 const geometry_msgs::msg::Vector3& offset)
597 Eigen::Quaterniond quat;
598 tf2::fromMsg(orientation, quat);
601 tf2::fromMsg(position, v);
603 Eigen::Isometry3d pose = Eigen::Translation3d(v) * quat;
605 tf2::fromMsg(offset, v);
606 pose.translation() -= quat * v;
612 return getConstraintPose(goal.position_constraints.front().constraint_region.primitive_poses.front().position,
613 goal.orientation_constraints.front().orientation,
614 goal.position_constraints.front().target_point_offset);
const std::string & getName() const
Get the name of the joint group.
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void copyJointGroupVelocities(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
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...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void update(bool force=false)
Update all transforms.
void copyJointGroupAccelerations(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
rclcpp::Logger getLogger()
Vec3fX< details::Vec3Data< double > > Vector3d
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
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 linearSearchIntersectionPoint(const std::string &link_name, const Eigen::Vector3d ¢er_position, const double r, const robot_trajectory::RobotTrajectoryPtr &traj, bool inverseOrder, std::size_t &index)
Performs a linear search for the intersection point of the trajectory with the blending radius.
bool isStateColliding(const planning_scene::PlanningSceneConstPtr &scene, moveit::core::RobotState *state, const moveit::core::JointModelGroup *const group, const double *const ik_solution)
Checks if current robot state is in self collision.
bool isRobotStateStationary(const moveit::core::RobotState &state, const std::string &group, double EPSILON)
check if the robot state have zero velocity/acceleration
bool determineAndCheckSamplingTime(const robot_trajectory::RobotTrajectoryPtr &first_trajectory, const robot_trajectory::RobotTrajectoryPtr &second_trajectory, double EPSILON, double &sampling_time)
Determines the sampling time and checks that both trajectroies use the same sampling time.
bool intersectionFound(const Eigen::Vector3d &p_center, const Eigen::Vector3d &p_current, const Eigen::Vector3d &p_next, double r)
bool verifySampleJointLimits(const std::map< std::string, double > &position_last, const std::map< std::string, double > &velocity_last, const std::map< std::string, double > &position_current, double duration_last, double duration_current, const JointLimitsContainer &joint_limits)
verify the velocity/acceleration limits of current sample (based on backward difference computation) ...
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
bool isRobotStateEqual(const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const std::string &joint_group_name, double epsilon)
Check if the two robot states have the same joint position/velocity/acceleration.
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)....
bool verbose
Flag indicating whether information about detected collisions should be reported.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
std::vector< CartesianTrajectoryPoint > points
void normalizeQuaternion(geometry_msgs::msg::Quaternion &quat)
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.