39 #include <tf2_eigen/tf2_eigen.hpp> 
   40 #include <tf2_kdl/tf2_kdl.hpp> 
   41 #include <boost/range/combine.hpp> 
   43 #include <kdl/velocityprofile_trap.hpp> 
   50 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.pilz_industrial_motion_planner.trajectory_generator");
 
   52 sensor_msgs::msg::JointState TrajectoryGenerator::filterGroupValues(
const sensor_msgs::msg::JointState& robot_state,
 
   53                                                                     const std::string& 
group)
 const 
   55   const std::vector<std::string>& group_joints{ 
robot_model_->getJointModelGroup(
group)->getActiveJointModelNames() };
 
   56   sensor_msgs::msg::JointState group_state;
 
   57   group_state.name.reserve(group_joints.size());
 
   58   group_state.position.reserve(group_joints.size());
 
   59   group_state.velocity.reserve(group_joints.size());
 
   61   for (
size_t i = 0; i < robot_state.name.size(); ++i)
 
   63     if (std::find(group_joints.begin(), group_joints.end(), robot_state.name.at(i)) != group_joints.end())
 
   65       group_state.name.push_back(robot_state.name.at(i));
 
   66       group_state.position.push_back(robot_state.position.at(i));
 
   67       if (i < robot_state.velocity.size())
 
   69         group_state.velocity.push_back(robot_state.velocity.at(i));
 
   82 void TrajectoryGenerator::checkVelocityScaling(
const double& scaling_factor)
 
   84   if (!isScalingFactorValid(scaling_factor))
 
   86     std::ostringstream os;
 
   88        << 
"actual value is: " << scaling_factor;
 
   89     throw VelocityScalingIncorrect(os.str());
 
   93 void TrajectoryGenerator::checkAccelerationScaling(
const double& scaling_factor)
 
   95   if (!isScalingFactorValid(scaling_factor))
 
   97     std::ostringstream os;
 
   99        << 
"actual value is: " << scaling_factor;
 
  100     throw AccelerationScalingIncorrect(os.str());
 
  104 void TrajectoryGenerator::checkForValidGroupName(
const std::string& group_name)
 const 
  108     std::ostringstream os;
 
  109     os << 
"Unknown planning group: " << group_name;
 
  110     throw UnknownPlanningGroup(os.str());
 
  114 void TrajectoryGenerator::checkStartState(
const moveit_msgs::msg::RobotState& start_state,
 
  115                                           const std::string& 
group)
 const 
  117   if (start_state.joint_state.name.size() != start_state.joint_state.position.size())
 
  119     throw SizeMismatchInStartState(
"Joint state name and position do not match in start state");
 
  122   sensor_msgs::msg::JointState group_start_state{ filterGroupValues(start_state.joint_state, 
group) };
 
  126   std::string error_msg;
 
  127   for (
auto joint : boost::combine(group_start_state.name, group_start_state.position))
 
  129     if (!limits.verifyPositionLimit(joint.get<0>(), joint.get<1>()))
 
  131       error_msg.append(error_msg.empty() ? 
"start state joints outside their position limits: " : 
", ");
 
  132       error_msg.append(joint.get<0>());
 
  135   if (!error_msg.empty())
 
  137     throw JointsOfStartStateOutOfRange(error_msg);
 
  141   if (!std::all_of(group_start_state.velocity.begin(), group_start_state.velocity.end(),
 
  142                    [
this](
double v) { return std::fabs(v) < this->VELOCITY_TOLERANCE; }))
 
  144     throw NonZeroVelocityInStartState(
"Trajectory Generator does not allow non-zero start velocity");
 
  148 void TrajectoryGenerator::checkJointGoalConstraint(
const moveit_msgs::msg::Constraints& constraint,
 
  149                                                    const std::string& group_name)
 const 
  151   for (
auto const& joint_constraint : constraint.joint_constraints)
 
  153     const std::string& curr_joint_name{ joint_constraint.joint_name };
 
  155     if (!
robot_model_->getJointModelGroup(group_name)->hasJointModel(curr_joint_name))
 
  157       std::ostringstream os;
 
  158       os << 
"Joint \"" << curr_joint_name << 
"\" does not belong to group \"" << group_name << 
"\"";
 
  159       throw JointConstraintDoesNotBelongToGroup(os.str());
 
  164       std::ostringstream os;
 
  165       os << 
"Joint \"" << curr_joint_name << 
"\" violates joint limits in goal constraints";
 
  166       throw JointsOfGoalOutOfRange(os.str());
 
  171 void TrajectoryGenerator::checkCartesianGoalConstraint(
const moveit_msgs::msg::Constraints& constraint,
 
  175   assert(constraint.position_constraints.size() == 1);
 
  176   assert(constraint.orientation_constraints.size() == 1);
 
  177   const moveit_msgs::msg::PositionConstraint& pos_constraint{ constraint.position_constraints.front() };
 
  178   const moveit_msgs::msg::OrientationConstraint& ori_constraint{ constraint.orientation_constraints.front() };
 
  180   if (pos_constraint.link_name.empty())
 
  182     throw PositionConstraintNameMissing(
"Link name of position constraint missing");
 
  185   if (ori_constraint.link_name.empty())
 
  187     throw OrientationConstraintNameMissing(
"Link name of orientation constraint missing");
 
  190   if (pos_constraint.link_name != ori_constraint.link_name)
 
  192     std::ostringstream os;
 
  193     os << 
"Position and orientation constraint name do not match" 
  194        << 
"(Position constraint name: \"" << pos_constraint.link_name << 
"\" | Orientation constraint name: \"" 
  195        << ori_constraint.link_name << 
"\")";
 
  196     throw PositionOrientationConstraintNameMismatch(os.str());
 
  202     std::ostringstream os;
 
  203     os << 
"No IK solver available for link: \"" << pos_constraint.link_name << 
"\"";
 
  204     throw NoIKSolverAvailable(os.str());
 
  207   if (pos_constraint.constraint_region.primitive_poses.empty())
 
  209     throw NoPrimitivePoseGiven(
"Primitive pose in position constraints of goal missing");
 
  213 void TrajectoryGenerator::checkGoalConstraints(
 
  214     const moveit_msgs::msg::MotionPlanRequest::_goal_constraints_type& goal_constraints, 
const std::string& group_name,
 
  217   if (goal_constraints.size() != 1)
 
  219     std::ostringstream os;
 
  220     os << 
"Exactly one goal constraint required, but " << goal_constraints.size() << 
" goal constraints given";
 
  221     throw NotExactlyOneGoalConstraintGiven(os.str());
 
  224   const moveit_msgs::msg::Constraints& goal_con{ goal_constraints.front() };
 
  225   if (!isOnlyOneGoalTypeGiven(goal_con))
 
  227     throw OnlyOneGoalTypeAllowed(
"Only cartesian XOR joint goal allowed");
 
  230   if (isJointGoalGiven(goal_con))
 
  232     checkJointGoalConstraint(goal_con, group_name);
 
  236     checkCartesianGoalConstraint(goal_con, rstate, 
robot_model_->getJointModelGroup(group_name));
 
  243   checkVelocityScaling(req.max_velocity_scaling_factor);
 
  244   checkAccelerationScaling(req.max_acceleration_scaling_factor);
 
  245   checkForValidGroupName(req.group_name);
 
  246   checkStartState(req.start_state, req.group_name);
 
  247   checkGoalConstraints(req.goal_constraints, req.group_name, rstate);
 
  250 void TrajectoryGenerator::setSuccessResponse(
const moveit::core::RobotState& start_state, 
const std::string& group_name,
 
  251                                              const trajectory_msgs::msg::JointTrajectory& joint_trajectory,
 
  252                                              const rclcpp::Time& planning_start,
 
  255   auto rt = std::make_shared<robot_trajectory::RobotTrajectory>(
robot_model_, group_name);
 
  256   rt->setRobotTrajectoryMsg(start_state, joint_trajectory);
 
  259   res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
  263 void TrajectoryGenerator::setFailureResponse(
const rclcpp::Time& planning_start,
 
  273 std::unique_ptr<KDL::VelocityProfile>
 
  275                                                   const double& max_acceleration_scaling_factor,
 
  276                                                   const std::unique_ptr<KDL::Path>& path)
 const 
  278   std::unique_ptr<KDL::VelocityProfile> vp_trans = std::make_unique<KDL::VelocityProfile_Trap>(
 
  282   if (path->PathLength() > std::numeric_limits<double>::epsilon())  
 
  284     vp_trans->SetProfile(0, path->PathLength());
 
  288     vp_trans->SetProfile(0, std::numeric_limits<double>::epsilon());
 
  297   RCLCPP_INFO_STREAM(LOGGER, 
"Generating " << req.planner_id << 
" trajectory...");
 
  298   rclcpp::Time planning_begin = 
clock_->now();
 
  302     validateRequest(req, 
scene->getCurrentState());
 
  306     RCLCPP_ERROR_STREAM(LOGGER, ex.what());
 
  308     setFailureResponse(planning_begin, res);
 
  314     cmdSpecificRequestValidation(req);
 
  318     RCLCPP_ERROR_STREAM(LOGGER, ex.what());
 
  320     setFailureResponse(planning_begin, res);
 
  327     extractMotionPlanInfo(
scene, req, plan_info);
 
  331     RCLCPP_ERROR_STREAM(LOGGER, ex.what());
 
  333     setFailureResponse(planning_begin, res);
 
  337   trajectory_msgs::msg::JointTrajectory joint_trajectory;
 
  340     plan(plan_info.
start_scene, req, plan_info, sampling_time, joint_trajectory);
 
  344     RCLCPP_ERROR_STREAM(LOGGER, ex.what());
 
  346     setFailureResponse(planning_begin, res);
 
  350   setSuccessResponse(plan_info.
start_scene->getCurrentState(), req.group_name, joint_trajectory, planning_begin, res);
 
  357   auto ps = 
scene->diff();
 
  358   auto& start_state = ps->getCurrentStateNonConst();
 
  366   for (
const auto* jm : start_state.
getRobotModel()->getJointModelGroup(req.group_name)->getActiveJointModels())
 
  368     const auto& names = jm->getVariableNames();
 
  369     for (std::size_t i = 0, j = jm->getFirstVariableIndex(); i < jm->getVariableCount(); ++i, ++j)
 
bool canSetStateFromIK(const std::string &tip) const
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
 
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
 
void update(bool force=false)
Update all transforms.
 
const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const std::string &frame, const moveit::core::JointModelGroup *jmg=nullptr) const
Get the latest link upwards the kinematic tree which is only connected via fixed joints.
 
double getMaxTranslationalAcceleration() const
Return the maximal translational acceleration [m/s^2], 0 if nothing was set.
 
double getMaxTranslationalVelocity() const
Return the maximal translational velocity [m/s], 0 if nothing was set.
 
bool verifyPositionLimit(const std::string &joint_name, const double &joint_position) const
verify position limit of single joint
 
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
 
const CartesianLimit & getCartesianLimits() const
Return the cartesian limits.
 
Exception storing an moveit_msgs::msg::MoveItErrorCodes value.
 
virtual const moveit_msgs::msg::MoveItErrorCodes::_val_type & getErrorCode() const =0
 
This class is used to extract needed information from motion plan request.
 
MotionPlanInfo(const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req)
 
planning_scene::PlanningSceneConstPtr start_scene
 
std::map< std::string, double > start_joint_position
 
const moveit::core::RobotModelConstPtr robot_model_
 
bool generate(const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, double sampling_time=0.1)
generate robot trajectory with given sampling time
 
std::unique_ptr< KDL::VelocityProfile > cartesianTrapVelocityProfile(const double &max_velocity_scaling_factor, const double &max_acceleration_scaling_factor, const std::unique_ptr< KDL::Path > &path) const
build cartesian velocity profile for the path
 
static constexpr double MIN_SCALING_FACTOR
 
const pilz_industrial_motion_planner::LimitsContainer planner_limits_
 
const std::unique_ptr< rclcpp::Clock > clock_
 
static constexpr double MAX_SCALING_FACTOR
 
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
 
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
 
robot_trajectory::RobotTrajectoryPtr trajectory_
 
moveit_msgs::msg::MoveItErrorCodes error_code_