43 #include <rclcpp/logger.hpp> 
   44 #include <rclcpp/logging.hpp> 
   45 #include <eigen3/Eigen/Core> 
   46 #include <eigen3/Eigen/LU> 
   48 #include <visualization_msgs/msg/marker_array.hpp> 
   52 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"chomp_optimizer");
 
   56   std::default_random_engine seed;
 
   57   std::uniform_real_distribution<> uniform(0.0, 1.0);
 
   64   : full_trajectory_(trajectory)
 
   66   , planning_group_(planning_group)
 
   67   , parameters_(parameters)
 
   68   , group_trajectory_(*full_trajectory_, planning_group_, DIFF_RULE_LENGTH)
 
   71   , start_state_(start_state)
 
   74   RCLCPP_INFO(LOGGER, 
"Active collision detector is: %s", 
planning_scene->getCollisionDetectorName().c_str());
 
   80     RCLCPP_WARN(LOGGER, 
"Could not initialize hybrid collision world from planning scene");
 
   87 void ChompOptimizer::initialize()
 
  101   const auto wt = std::chrono::system_clock::now();
 
  102   hy_env_->
getCollisionGradients(req, res, state_, &planning_scene_->getAllowedCollisionMatrix(), gsr_);
 
  103   RCLCPP_INFO(LOGGER, 
"First coll check took %f sec",
 
  104               std::chrono::duration<double>(std::chrono::system_clock::now() - wt).count());
 
  105   num_collision_points_ = 0;
 
  108     num_collision_points_ += gradient.
gradients.size();
 
  112   joint_costs_.reserve(num_joints_);
 
  114   double max_cost_scale = 0.0;
 
  116   joint_model_group_ = planning_scene_->getRobotModel()->getJointModelGroup(planning_group_);
 
  118   const std::vector<const moveit::core::JointModel*> joint_models = joint_model_group_->
getActiveJointModels();
 
  119   for (
size_t i = 0; i < joint_models.size(); ++i)
 
  121     double joint_cost = 1.0;
 
  123     std::vector<double> derivative_costs(3);
 
  127     joint_costs_.push_back(ChompCost(group_trajectory_, i, derivative_costs, parameters_->
ridge_factor_));
 
  128     double cost_scale = joint_costs_[i].getMaxQuadCostInvValue();
 
  129     if (max_cost_scale < cost_scale)
 
  130       max_cost_scale = cost_scale;
 
  134   for (
int i = 0; i < num_joints_; ++i)
 
  136     joint_costs_[i].scale(max_cost_scale);
 
  140   smoothness_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
 
  141   collision_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
 
  142   final_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
 
  143   smoothness_derivative_ = Eigen::VectorXd::Zero(num_vars_all_);
 
  144   jacobian_ = Eigen::MatrixXd::Zero(3, num_joints_);
 
  145   jacobian_pseudo_inverse_ = Eigen::MatrixXd::Zero(num_joints_, 3);
 
  146   jacobian_jacobian_tranpose_ = Eigen::MatrixXd::Zero(3, 3);
 
  147   random_state_ = Eigen::VectorXd::Zero(num_joints_);
 
  148   joint_state_velocities_ = Eigen::VectorXd::Zero(num_joints_);
 
  150   group_trajectory_backup_ = group_trajectory_.
getTrajectory();
 
  153   collision_point_joint_names_.resize(num_vars_all_, std::vector<std::string>(num_collision_points_));
 
  154   collision_point_pos_eigen_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_collision_points_));
 
  155   collision_point_vel_eigen_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_collision_points_));
 
  156   collision_point_acc_eigen_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_collision_points_));
 
  157   joint_axes_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_joints_));
 
  158   joint_positions_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_joints_));
 
  160   collision_point_potential_.resize(num_vars_all_, std::vector<double>(num_collision_points_));
 
  161   collision_point_vel_mag_.resize(num_vars_all_, std::vector<double>(num_collision_points_));
 
  162   collision_point_potential_gradient_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_collision_points_));
 
  164   collision_free_iteration_ = 0;
 
  165   is_collision_free_ = 
false;
 
  166   state_is_in_collision_.resize(num_vars_all_);
 
  167   point_is_in_collision_.resize(num_vars_all_, std::vector<int>(num_collision_points_));
 
  169   last_improvement_iteration_ = -1;
 
  178   multivariate_gaussian_.clear();
 
  179   stochasticity_factor_ = 1.0;
 
  180   for (
int i = 0; i < num_joints_; ++i)
 
  182     multivariate_gaussian_.push_back(
 
  183         MultivariateGaussian(Eigen::VectorXd::Zero(num_vars_free_), joint_costs_[i].getQuadraticCostInverse()));
 
  186   std::map<std::string, std::string> fixed_link_resolution_map;
 
  187   for (
int i = 0; i < num_joints_; ++i)
 
  192     fixed_link_resolution_map[joint_names_[i]] = joint_names_[i];
 
  197     if (!jm->getParentLinkModel())  
 
  200     fixed_link_resolution_map[jm->getName()] = jm->getParentLinkModel()->getParentJointModel()->getName();
 
  206     if (fixed_link_resolution_map.find(link->getParentJointModel()->getName()) == fixed_link_resolution_map.end())
 
  209       bool found_root = 
false;
 
  213         if (parent_model == 
nullptr)
 
  215           parent_model = link->getParentJointModel();
 
  220           for (
const std::string& joint_name : joint_names_)
 
  222             if (parent_model->
getName() == joint_name)
 
  229       fixed_link_resolution_map[link->getParentJointModel()->getName()] = parent_model->
getName();
 
  233   int start = free_vars_start_;
 
  234   int end = free_vars_end_;
 
  235   for (
int i = start; i <= end; ++i)
 
  242         if (fixed_link_resolution_map.find(info.
joint_name) != fixed_link_resolution_map.end())
 
  244           collision_point_joint_names_[i][j] = fixed_link_resolution_map[info.
joint_name];
 
  248           RCLCPP_ERROR(LOGGER, 
"Couldn't find joint %s!", info.
joint_name.c_str());
 
  265   bool found_root = 
false;
 
  267   if (model == robot_model_->getRootJoint())
 
  272     if (parent_model == 
nullptr)
 
  276         RCLCPP_ERROR(LOGGER, 
"Model %s not root but has nullptr link model parent", model->
getName().c_str());
 
  281         RCLCPP_ERROR(LOGGER, 
"Model %s not root but has nullptr joint model parent", model->
getName().c_str());
 
  288       if (parent_model == robot_model_->getRootJoint())
 
  297     joint_parent_map_[model->
getName()][parent_model->
getName()] = 
true;
 
  303   bool optimization_result = 0;
 
  305   const auto start_time = std::chrono::system_clock::now();
 
  308   int cost_window = 10;
 
  309   std::vector<double> costs(cost_window, 0.0);
 
  311   bool should_break_out = 
false;
 
  314   for (iteration_ = 0; iteration_ < parameters_->
max_iterations_; ++iteration_)
 
  316     performForwardKinematics();
 
  317     double c_cost = getCollisionCost();
 
  318     double s_cost = getSmoothnessCost();
 
  319     double cost = c_cost + s_cost;
 
  321     RCLCPP_INFO(LOGGER, 
"Collision cost %f, smoothness cost: %f", c_cost, s_cost);
 
  346       best_group_trajectory_cost_ = cost;
 
  347       last_improvement_iteration_ = iteration_;
 
  349     else if (cost < best_group_trajectory_cost_)
 
  352       best_group_trajectory_cost_ = cost;
 
  353       last_improvement_iteration_ = iteration_;
 
  355     calculateSmoothnessIncrements();
 
  356     calculateCollisionIncrements();
 
  357     calculateTotalIncrements();
 
  365     addIncrementsToTrajectory();
 
  377     updateFullTrajectory();
 
  379     if (iteration_ % 10 == 0)
 
  381       RCLCPP_INFO(LOGGER, 
"iteration: %d", iteration_);
 
  382       if (isCurrentTrajectoryMeshToMeshCollisionFree())
 
  384         num_collision_free_iterations_ = 0;
 
  385         RCLCPP_INFO(LOGGER, 
"Chomp Got mesh to mesh safety at iter %d. Breaking out early.", iteration_);
 
  386         is_collision_free_ = 
true;
 
  388         should_break_out = 
true;
 
  419       if (c_cost < parameters_->collision_threshold_)
 
  422         is_collision_free_ = 
true;
 
  424         should_break_out = 
true;
 
  432     if (std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count() >
 
  435       RCLCPP_WARN(LOGGER, 
"Breaking out early due to time limit constraints.");
 
  488     if (should_break_out)
 
  490       collision_free_iteration_++;
 
  491       if (num_collision_free_iterations_ == 0)
 
  495       else if (collision_free_iteration_ > num_collision_free_iterations_)
 
  507   if (is_collision_free_)
 
  509     optimization_result = 
true;
 
  510     RCLCPP_INFO(LOGGER, 
"Chomp path is collision free");
 
  514     optimization_result = 
false;
 
  515     RCLCPP_ERROR(LOGGER, 
"Chomp path is not collision free!");
 
  519   updateFullTrajectory();
 
  521   RCLCPP_INFO(LOGGER, 
"Terminated after %d iterations, using path from iteration %d", iteration_,
 
  522               last_improvement_iteration_);
 
  523   RCLCPP_INFO(LOGGER, 
"Optimization core finished in %f sec",
 
  524               std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count());
 
  525   RCLCPP_INFO(LOGGER, 
"Time per iteration %f sec",
 
  526               std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count() / (iteration_ * 1.0));
 
  528   return optimization_result;
 
  531 bool ChompOptimizer::isCurrentTrajectoryMeshToMeshCollisionFree()
 const 
  533   moveit_msgs::msg::RobotTrajectory traj;
 
  534   traj.joint_trajectory.joint_names = joint_names_;
 
  536   for (
size_t i = 0; i < group_trajectory_.
getNumPoints(); ++i)
 
  538     trajectory_msgs::msg::JointTrajectoryPoint point;
 
  539     for (
size_t j = 0; j < group_trajectory_.
getNumJoints(); ++j)
 
  541       point.positions.push_back(best_group_trajectory_(i, j));
 
  543     traj.joint_trajectory.points.push_back(point);
 
  545   moveit_msgs::msg::RobotState start_state_msg;
 
  547   return planning_scene_->isPathValid(start_state_msg, traj, planning_group_);
 
  584 void ChompOptimizer::calculateSmoothnessIncrements()
 
  586   for (
int i = 0; i < num_joints_; ++i)
 
  588     joint_costs_[i].getDerivative(group_trajectory_.
getJointTrajectory(i), smoothness_derivative_);
 
  589     smoothness_increments_.col(i) = -smoothness_derivative_.segment(group_trajectory_.
getStartIndex(), num_vars_free_);
 
  593 void ChompOptimizer::calculateCollisionIncrements()
 
  600   Eigen::Matrix3d orthogonal_projector;
 
  604   collision_increments_.setZero(num_vars_free_, num_joints_);
 
  607   int end_point = free_vars_end_;
 
  613     start_point = 
static_cast<int>(
getRandomDouble() * (free_vars_end_ - free_vars_start_) + free_vars_start_);
 
  614     if (start_point < free_vars_start_)
 
  615       start_point = free_vars_start_;
 
  616     if (start_point > free_vars_end_)
 
  617       start_point = free_vars_end_;
 
  618     end_point = start_point;
 
  622     start_point = free_vars_start_;
 
  625   for (
int i = start_point; i <= end_point; ++i)
 
  627     for (
int j = 0; j < num_collision_points_; ++j)
 
  629       potential = collision_point_potential_[i][j];
 
  631       if (potential < 0.0001)
 
  634       potential_gradient = -collision_point_potential_gradient_[i][j];
 
  636       vel_mag = collision_point_vel_mag_[i][j];
 
  637       vel_mag_sq = vel_mag * vel_mag;
 
  641       normalized_velocity = collision_point_vel_eigen_[i][j] / vel_mag;
 
  642       orthogonal_projector = Eigen::Matrix3d::Identity() - (normalized_velocity * normalized_velocity.transpose());
 
  643       curvature_vector = (orthogonal_projector * collision_point_acc_eigen_[i][j]) / vel_mag_sq;
 
  644       cartesian_gradient = vel_mag * (orthogonal_projector * potential_gradient - potential * curvature_vector);
 
  647       getJacobian(i, collision_point_pos_eigen_[i][j], collision_point_joint_names_[i][j], jacobian_);
 
  651         calculatePseudoInverse();
 
  652         collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_pseudo_inverse_ * cartesian_gradient;
 
  656         collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_.transpose() * cartesian_gradient;
 
  670 void ChompOptimizer::calculatePseudoInverse()
 
  672   jacobian_jacobian_tranpose_ =
 
  674   jacobian_pseudo_inverse_ = jacobian_.transpose() * jacobian_jacobian_tranpose_.inverse();
 
  677 void ChompOptimizer::calculateTotalIncrements()
 
  679   for (
int i = 0; i < num_joints_; ++i)
 
  681     final_increments_.col(i) =
 
  682         parameters_->
learning_rate_ * (joint_costs_[i].getQuadraticCostInverse() *
 
  688 void ChompOptimizer::addIncrementsToTrajectory()
 
  690   const std::vector<const moveit::core::JointModel*>& joint_models = joint_model_group_->
getActiveJointModels();
 
  691   for (
size_t i = 0; i < joint_models.size(); ++i)
 
  694     double max = final_increments_.col(i).maxCoeff();
 
  695     double min = final_increments_.col(i).minCoeff();
 
  698     if (max_scale < scale)
 
  700     if (min_scale < scale)
 
  708 void ChompOptimizer::updateFullTrajectory()
 
  713 void ChompOptimizer::debugCost()
 
  716   for (
int i = 0; i < num_joints_; ++i)
 
  718   std::cout << 
"Cost = " << cost << 
'\n';
 
  721 double ChompOptimizer::getTrajectoryCost()
 
  723   return getSmoothnessCost() + getCollisionCost();
 
  726 double ChompOptimizer::getSmoothnessCost()
 
  728   double smoothness_cost = 0.0;
 
  730   for (
int i = 0; i < num_joints_; ++i)
 
  736 double ChompOptimizer::getCollisionCost()
 
  738   double collision_cost = 0.0;
 
  740   double worst_collision_cost = 0.0;
 
  741   worst_collision_cost_state_ = -1;
 
  744   for (
int i = free_vars_start_; i <= free_vars_end_; ++i)
 
  746     double state_collision_cost = 0.0;
 
  747     for (
int j = 0; j < num_collision_points_; ++j)
 
  749       state_collision_cost += collision_point_potential_[i][j] * collision_point_vel_mag_[i][j];
 
  751     collision_cost += state_collision_cost;
 
  752     if (state_collision_cost > worst_collision_cost)
 
  754       worst_collision_cost = state_collision_cost;
 
  755       worst_collision_cost_state_ = i;
 
  762 void ChompOptimizer::computeJointProperties(
int trajectory_point)
 
  764   for (
int j = 0; j < num_joints_; ++j)
 
  775                                         (robot_model_->getLinkModel(child_link_name)->getJointOriginTransform() *
 
  781     if (revolute_joint != 
nullptr)
 
  783       axis = revolute_joint->
getAxis();
 
  785     else if (prismatic_joint != 
nullptr)
 
  787       axis = prismatic_joint->
getAxis();
 
  791       axis = Eigen::Vector3d::Identity();
 
  794     axis = joint_transform * axis;
 
  796     joint_axes_[trajectory_point][j] = axis;
 
  797     joint_positions_[trajectory_point][j] = joint_transform.translation();
 
  801 template <
typename Derived>
 
  802 void ChompOptimizer::getJacobian(
int trajectory_point, 
Eigen::Vector3d& collision_point_pos, std::string& joint_name,
 
  803                                  Eigen::MatrixBase<Derived>& jacobian)
 const 
  805   for (
int j = 0; j < num_joints_; ++j)
 
  807     if (isParent(joint_name, joint_names_[j]))
 
  810           Eigen::Vector3d(collision_point_pos(0), collision_point_pos(1), collision_point_pos(2)) -
 
  811           joint_positions_[trajectory_point][j]);
 
  813       jacobian.col(j)[0] = column.x();
 
  814       jacobian.col(j)[1] = column.y();
 
  815       jacobian.col(j)[2] = column.z();
 
  819       jacobian.col(j)[0] = 0.0;
 
  820       jacobian.col(j)[1] = 0.0;
 
  821       jacobian.col(j)[2] = 0.0;
 
  826 void ChompOptimizer::handleJointLimits()
 
  828   const std::vector<const moveit::core::JointModel*> joint_models = joint_model_group_->
getActiveJointModels();
 
  829   for (
size_t joint_i = 0; joint_i < joint_models.size(); ++joint_i)
 
  845     double joint_max = -DBL_MAX;
 
  846     double joint_min = DBL_MAX;
 
  850       if (bound.min_position_ < joint_min)
 
  855       if (bound.max_position_ > joint_max)
 
  857         joint_max = bound.max_position_;
 
  863     bool violation = 
false;
 
  866       double max_abs_violation = 1e-6;
 
  867       double max_violation = 0.0;
 
  868       int max_violation_index = 0;
 
  870       for (
int i = free_vars_start_; i <= free_vars_end_; ++i)
 
  873         double absolute_amount = 0.0;
 
  874         if (group_trajectory_(i, joint_i) > joint_max)
 
  876           amount = joint_max - group_trajectory_(i, joint_i);
 
  877           absolute_amount = fabs(amount);
 
  879         else if (group_trajectory_(i, joint_i) < joint_min)
 
  881           amount = joint_min - group_trajectory_(i, joint_i);
 
  882           absolute_amount = fabs(amount);
 
  884         if (absolute_amount > max_abs_violation)
 
  886           max_abs_violation = absolute_amount;
 
  887           max_violation = amount;
 
  888           max_violation_index = i;
 
  895         int free_var_index = max_violation_index - free_vars_start_;
 
  897             max_violation / joint_costs_[joint_i].getQuadraticCostInverse()(free_var_index, free_var_index);
 
  899             multiplier * joint_costs_[joint_i].getQuadraticCostInverse().col(free_var_index);
 
  907 void ChompOptimizer::performForwardKinematics()
 
  910   double inv_time_sq = inv_time * inv_time;
 
  913   int start = free_vars_start_;
 
  914   int end = free_vars_end_;
 
  918     end = num_vars_all_ - 1;
 
  921   is_collision_free_ = 
true;
 
  923   auto total_dur = std::chrono::duration<double>::zero();
 
  926   for (
int i = start; i <= end; ++i)
 
  932     setRobotStateFromPoint(group_trajectory_, i);
 
  933     auto grad = std::chrono::system_clock::now();
 
  936     total_dur += (std::chrono::system_clock::now() - grad);
 
  937     computeJointProperties(i);
 
  938     state_is_in_collision_[i] = 
false;
 
  951           collision_point_potential_[i][j] =
 
  953           collision_point_potential_gradient_[i][j][0] = info.
gradients[k].x();
 
  954           collision_point_potential_gradient_[i][j][1] = info.
gradients[k].y();
 
  955           collision_point_potential_gradient_[i][j][2] = info.
gradients[k].z();
 
  959           if (point_is_in_collision_[i][j])
 
  961             state_is_in_collision_[i] = 
true;
 
  972             is_collision_free_ = 
false;
 
  983   for (
int i = free_vars_start_; i <= free_vars_end_; ++i)
 
  985     for (
int j = 0; j < num_collision_points_; ++j)
 
  989       for (
int k = -DIFF_RULE_LENGTH / 2; k <= DIFF_RULE_LENGTH / 2; ++k)
 
  991         collision_point_vel_eigen_[i][j] +=
 
  992             (inv_time * DIFF_RULES[0][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
 
  993         collision_point_acc_eigen_[i][j] +=
 
  994             (inv_time_sq * DIFF_RULES[1][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
 
  998       collision_point_vel_mag_[i][j] = collision_point_vel_eigen_[i][j].norm();
 
 1003 void ChompOptimizer::setRobotStateFromPoint(ChompTrajectory& group_trajectory, 
int i)
 
 1005   const Eigen::MatrixXd::RowXpr& point = group_trajectory.getTrajectoryPoint(i);
 
 1007   std::vector<double> joint_states;
 
 1008   joint_states.reserve(group_trajectory.getNumJoints());
 
 1009   for (
size_t j = 0; j < group_trajectory.getNumJoints(); ++j)
 
 1010     joint_states.emplace_back(point(0, j));
 
 1016 void ChompOptimizer::perturbTrajectory()
 
 1019   if (worst_collision_cost_state_ < 0)
 
 1021   int mid_point = worst_collision_cost_state_;
 
 1025   std::vector<double> vals;
 
 1027   double* ptr = &vals[0];
 
 1028   Eigen::Map<Eigen::VectorXd> random_matrix(ptr, vals.size());
 
 1036   joint_state_velocities_.normalize();
 
 1037   random_matrix = (Eigen::MatrixXd::Identity(num_joints_, num_joints_) -
 
 1038                    joint_state_velocities_ * joint_state_velocities_.transpose()) *
 
 1041   int mp_free_vars_index = mid_point - free_vars_start_;
 
 1042   for (
int i = 0; i < num_joints_; ++i)
 
 1045         joint_costs_[i].getQuadraticCostInverse().col(mp_free_vars_index) * random_state_(i);
 
ChompOptimizer(ChompTrajectory *trajectory, const planning_scene::PlanningSceneConstPtr &planning_scene, const std::string &planning_group, const ChompParameters *parameters, const moveit::core::RobotState &start_state)
 
virtual ~ChompOptimizer()
 
double collision_threshold_
 
double planning_time_limit_
 
double smoothness_cost_weight_
 
double smoothness_cost_jerk_
 
double smoothness_cost_acceleration_
 
bool use_stochastic_descent_
 
double pseudo_inverse_ridge_factor_
 
double smoothness_cost_velocity_
 
int max_iterations_after_collision_free_
 
double joint_update_limit_
 
double obstacle_cost_weight_
 
Represents a discretized joint-space trajectory for CHOMP.
 
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.
 
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
 
size_t getEndIndex() const
Gets the end index.
 
size_t getStartIndex() const
Gets the start index.
 
double getDiscretization() const
Gets the discretization time interval of the trajectory.
 
size_t getNumPoints() const
Gets the number of points in the trajectory.
 
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeJointTrajectoryBlock(size_t joint)
Gets the block of free (optimizable) trajectory for a single joint.
 
void getJointVelocities(size_t traj_point, Eigen::MatrixBase< Derived > &velocities)
Gets the joint velocities at the given trajectory point.
 
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
 
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
 
Eigen::MatrixXd::ColXpr getJointTrajectory(int joint)
 
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
 
size_t getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
 
This hybrid collision environment combines FCL and a distance field. Both can be used to calculate co...
 
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
 
const std::vector< const JointModel * > & getFixedJointModels() const
Get the fixed joints that are part of this group.
 
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
 
const std::vector< const LinkModel * > & getUpdatedLinkModels() const
Get the names of the links that are to be updated when the state of this group changes....
 
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
 
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
 
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
 
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
 
const std::string & getName() const
Get the name of the joint.
 
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
 
JointType getType() const
Get the type of joint.
 
A link from the robot. Contains the constant transform applied to the link and its geometry.
 
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
 
const std::string & getName() const
The name of this link.
 
const Eigen::Vector3d & getAxis() const
Get the axis of translation.
 
bool isContinuous() const
Check if this joint wraps around.
 
const Eigen::Vector3d & getAxis() const
Get the axis of rotation.
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
 
const JointModel * getJointModel(const std::string &joint) const
Get the model of a particular joint.
 
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
 
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 JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
 
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
 
void update(bool force=false)
Update all transforms.
 
Vec3fX< details::Vec3Data< double > > Vector3d
 
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.
 
This namespace includes the central class for representing planning contexts.
 
Representation of a collision checking request.
 
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
 
Representation of a collision checking result.
 
EigenSTL::vector_Vector3d gradients
 
std::vector< double > distances
 
std::vector< double > sphere_radii
 
EigenSTL::vector_Vector3d sphere_locations