44#include <rclcpp/logger.hpp>
45#include <rclcpp/logging.hpp>
46#include <eigen3/Eigen/Core>
47#include <eigen3/Eigen/LU>
49#include <visualization_msgs/msg/marker_array.hpp>
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(getLogger(),
"Active collision detector is: %s",
planning_scene->getCollisionDetectorName().c_str());
80 RCLCPP_WARN(getLogger(),
"Could not initialize hybrid collision world from planning scene");
87void 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(getLogger(),
"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())
215 if (std::find(joint_names_.begin(), joint_names_.end(), parent_model->
getName()) != joint_names_.end())
218 fixed_link_resolution_map[link->getParentJointModel()->getName()] = parent_model->
getName();
222 int start = free_vars_start_;
223 int end = free_vars_end_;
224 for (
int i = start; i <= end; ++i)
229 for (
size_t k = 0; k < info.sphere_locations.size(); ++k)
231 if (fixed_link_resolution_map.find(info.joint_name) != fixed_link_resolution_map.end())
233 collision_point_joint_names_[i][j] = fixed_link_resolution_map[info.joint_name];
237 RCLCPP_ERROR(
getLogger(),
"Couldn't find joint %s!", info.joint_name.c_str());
254 bool found_root =
false;
256 if (model == robot_model_->getRootJoint())
261 if (parent_model ==
nullptr)
265 RCLCPP_ERROR(getLogger(),
"Model %s not root but has nullptr link model parent", model->
getName().c_str());
270 RCLCPP_ERROR(getLogger(),
"Model %s not root but has nullptr joint model parent", model->
getName().c_str());
277 if (parent_model == robot_model_->getRootJoint())
286 joint_parent_map_[model->
getName()][parent_model->
getName()] =
true;
292 bool optimization_result = 0;
294 const auto start_time = std::chrono::system_clock::now();
297 int cost_window = 10;
298 std::vector<double> costs(cost_window, 0.0);
300 bool should_break_out =
false;
303 for (iteration_ = 0; iteration_ < parameters_->
max_iterations_; ++iteration_)
305 performForwardKinematics();
306 double c_cost = getCollisionCost();
307 double s_cost = getSmoothnessCost();
308 double cost = c_cost + s_cost;
310 RCLCPP_DEBUG(getLogger(),
"Collision cost %f, smoothness cost: %f", c_cost, s_cost);
335 best_group_trajectory_cost_ = cost;
336 last_improvement_iteration_ = iteration_;
338 else if (cost < best_group_trajectory_cost_)
341 best_group_trajectory_cost_ = cost;
342 last_improvement_iteration_ = iteration_;
344 calculateSmoothnessIncrements();
345 calculateCollisionIncrements();
346 calculateTotalIncrements();
354 addIncrementsToTrajectory();
366 updateFullTrajectory();
368 if (iteration_ % 10 == 0)
370 RCLCPP_DEBUG(getLogger(),
"iteration: %d", iteration_);
371 if (isCurrentTrajectoryMeshToMeshCollisionFree())
373 num_collision_free_iterations_ = 0;
374 RCLCPP_INFO(getLogger(),
"Chomp Got mesh to mesh safety at iter %d. Breaking out early.", iteration_);
375 is_collision_free_ =
true;
377 should_break_out =
true;
408 if (c_cost < parameters_->collision_threshold_)
411 is_collision_free_ =
true;
413 should_break_out =
true;
417 RCLCPP_DEBUG(getLogger(),
"cCost %f over threshold %f", c_cost, parameters_->
collision_threshold_);
421 if (std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count() >
424 RCLCPP_WARN(getLogger(),
"Breaking out early due to time limit constraints.");
477 if (should_break_out)
479 collision_free_iteration_++;
480 if (num_collision_free_iterations_ == 0)
484 else if (collision_free_iteration_ > num_collision_free_iterations_)
496 if (is_collision_free_)
498 optimization_result =
true;
499 RCLCPP_INFO(getLogger(),
"Chomp path is collision free");
503 optimization_result =
false;
504 RCLCPP_ERROR(getLogger(),
"Chomp path is not collision free!");
508 updateFullTrajectory();
510 RCLCPP_INFO(getLogger(),
"Terminated after %d iterations, using path from iteration %d", iteration_,
511 last_improvement_iteration_);
512 RCLCPP_INFO(getLogger(),
"Optimization core finished in %f sec",
513 std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count());
514 RCLCPP_INFO(getLogger(),
"Time per iteration %f sec",
515 std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count() / (iteration_ * 1.0));
517 return optimization_result;
520bool ChompOptimizer::isCurrentTrajectoryMeshToMeshCollisionFree()
const
522 moveit_msgs::msg::RobotTrajectory traj;
523 traj.joint_trajectory.joint_names = joint_names_;
525 for (
size_t i = 0; i < group_trajectory_.
getNumPoints(); ++i)
527 trajectory_msgs::msg::JointTrajectoryPoint point;
528 for (
size_t j = 0; j < group_trajectory_.
getNumJoints(); ++j)
530 point.positions.push_back(best_group_trajectory_(i, j));
532 traj.joint_trajectory.points.push_back(point);
534 moveit_msgs::msg::RobotState start_state_msg;
536 return planning_scene_->isPathValid(start_state_msg, traj, planning_group_);
539void ChompOptimizer::calculateSmoothnessIncrements()
541 for (
int i = 0; i < num_joints_; ++i)
543 joint_costs_[i].getDerivative(group_trajectory_.
getJointTrajectory(i), smoothness_derivative_);
544 smoothness_increments_.col(i) = -smoothness_derivative_.segment(group_trajectory_.
getStartIndex(), num_vars_free_);
548void ChompOptimizer::calculateCollisionIncrements()
553 Eigen::Vector3d potential_gradient;
554 Eigen::Vector3d normalized_velocity;
555 Eigen::Matrix3d orthogonal_projector;
556 Eigen::Vector3d curvature_vector;
557 Eigen::Vector3d cartesian_gradient;
559 collision_increments_.setZero(num_vars_free_, num_joints_);
562 int end_point = free_vars_end_;
568 start_point =
static_cast<int>(rsl::uniform_real(0., 1.) * (free_vars_end_ - free_vars_start_) + free_vars_start_);
569 if (start_point < free_vars_start_)
570 start_point = free_vars_start_;
571 if (start_point > free_vars_end_)
572 start_point = free_vars_end_;
573 end_point = start_point;
577 start_point = free_vars_start_;
580 for (
int i = start_point; i <= end_point; ++i)
582 for (
int j = 0; j < num_collision_points_; ++j)
584 potential = collision_point_potential_[i][j];
586 if (potential < 0.0001)
589 potential_gradient = -collision_point_potential_gradient_[i][j];
591 vel_mag = collision_point_vel_mag_[i][j];
592 vel_mag_sq = vel_mag * vel_mag;
596 normalized_velocity = collision_point_vel_eigen_[i][j] / vel_mag;
597 orthogonal_projector = Eigen::Matrix3d::Identity() - (normalized_velocity * normalized_velocity.transpose());
598 curvature_vector = (orthogonal_projector * collision_point_acc_eigen_[i][j]) / vel_mag_sq;
599 cartesian_gradient = vel_mag * (orthogonal_projector * potential_gradient - potential * curvature_vector);
602 getJacobian(i, collision_point_pos_eigen_[i][j], collision_point_joint_names_[i][j], jacobian_);
606 calculatePseudoInverse();
607 collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_pseudo_inverse_ * cartesian_gradient;
611 collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_.transpose() * cartesian_gradient;
625void ChompOptimizer::calculatePseudoInverse()
627 jacobian_jacobian_tranpose_ =
629 jacobian_pseudo_inverse_ = jacobian_.transpose() * jacobian_jacobian_tranpose_.inverse();
632void ChompOptimizer::calculateTotalIncrements()
634 for (
int i = 0; i < num_joints_; ++i)
636 final_increments_.col(i) =
637 parameters_->
learning_rate_ * (joint_costs_[i].getQuadraticCostInverse() *
643void ChompOptimizer::addIncrementsToTrajectory()
645 const std::vector<const moveit::core::JointModel*>& joint_models = joint_model_group_->
getActiveJointModels();
646 for (
size_t i = 0; i < joint_models.size(); ++i)
649 double max = final_increments_.col(i).maxCoeff();
650 double min = final_increments_.col(i).minCoeff();
653 if (max_scale < scale)
655 if (min_scale < scale)
663void ChompOptimizer::updateFullTrajectory()
668void ChompOptimizer::debugCost()
671 for (
int i = 0; i < num_joints_; ++i)
673 std::cout <<
"Cost = " << cost <<
'\n';
676double ChompOptimizer::getTrajectoryCost()
678 return getSmoothnessCost() + getCollisionCost();
681double ChompOptimizer::getSmoothnessCost()
683 double smoothness_cost = 0.0;
685 for (
int i = 0; i < num_joints_; ++i)
691double ChompOptimizer::getCollisionCost()
693 double collision_cost = 0.0;
695 double worst_collision_cost = 0.0;
696 worst_collision_cost_state_ = -1;
699 for (
int i = free_vars_start_; i <= free_vars_end_; ++i)
701 double state_collision_cost = 0.0;
702 for (
int j = 0; j < num_collision_points_; ++j)
704 state_collision_cost += collision_point_potential_[i][j] * collision_point_vel_mag_[i][j];
706 collision_cost += state_collision_cost;
707 if (state_collision_cost > worst_collision_cost)
709 worst_collision_cost = state_collision_cost;
710 worst_collision_cost_state_ = i;
717void ChompOptimizer::computeJointProperties(
int trajectory_point)
719 for (
int j = 0; j < num_joints_; ++j)
730 (robot_model_->getLinkModel(child_link_name)->getJointOriginTransform() *
734 Eigen::Vector3d axis;
736 if (revolute_joint !=
nullptr)
738 axis = revolute_joint->
getAxis();
740 else if (prismatic_joint !=
nullptr)
742 axis = prismatic_joint->
getAxis();
746 axis = Eigen::Vector3d::Identity();
749 axis = joint_transform * axis;
751 joint_axes_[trajectory_point][j] = axis;
752 joint_positions_[trajectory_point][j] = joint_transform.translation();
756template <
typename Derived>
757void ChompOptimizer::getJacobian(
int trajectory_point, Eigen::Vector3d& collision_point_pos, std::string& joint_name,
758 Eigen::MatrixBase<Derived>& jacobian)
const
760 for (
int j = 0; j < num_joints_; ++j)
762 if (isParent(joint_name, joint_names_[j]))
764 Eigen::Vector3d column = joint_axes_[trajectory_point][j].cross(
765 Eigen::Vector3d(collision_point_pos(0), collision_point_pos(1), collision_point_pos(2)) -
766 joint_positions_[trajectory_point][j]);
768 jacobian.col(j)[0] = column.x();
769 jacobian.col(j)[1] = column.y();
770 jacobian.col(j)[2] = column.z();
774 jacobian.col(j)[0] = 0.0;
775 jacobian.col(j)[1] = 0.0;
776 jacobian.col(j)[2] = 0.0;
781void ChompOptimizer::handleJointLimits()
783 const std::vector<const moveit::core::JointModel*> joint_models = joint_model_group_->
getActiveJointModels();
784 for (
size_t joint_i = 0; joint_i < joint_models.size(); ++joint_i)
800 double joint_max = -DBL_MAX;
801 double joint_min = DBL_MAX;
805 if (bound.min_position_ < joint_min)
810 if (bound.max_position_ > joint_max)
812 joint_max = bound.max_position_;
818 bool violation =
false;
821 double max_abs_violation = 1e-6;
822 double max_violation = 0.0;
823 int max_violation_index = 0;
825 for (
int i = free_vars_start_; i <= free_vars_end_; ++i)
828 double absolute_amount = 0.0;
829 if (group_trajectory_(i, joint_i) > joint_max)
831 amount = joint_max - group_trajectory_(i, joint_i);
832 absolute_amount = fabs(amount);
834 else if (group_trajectory_(i, joint_i) < joint_min)
836 amount = joint_min - group_trajectory_(i, joint_i);
837 absolute_amount = fabs(amount);
839 if (absolute_amount > max_abs_violation)
841 max_abs_violation = absolute_amount;
842 max_violation = amount;
843 max_violation_index = i;
850 int free_var_index = max_violation_index - free_vars_start_;
852 max_violation / joint_costs_[joint_i].getQuadraticCostInverse()(free_var_index, free_var_index);
854 multiplier * joint_costs_[joint_i].getQuadraticCostInverse().col(free_var_index);
862void ChompOptimizer::performForwardKinematics()
865 double inv_time_sq = inv_time * inv_time;
868 int start = free_vars_start_;
869 int end = free_vars_end_;
873 end = num_vars_all_ - 1;
876 is_collision_free_ =
true;
878 auto total_dur = std::chrono::duration<double>::zero();
881 for (
int i = start; i <= end; ++i)
887 setRobotStateFromPoint(group_trajectory_, i);
888 auto grad = std::chrono::system_clock::now();
891 total_dur += (std::chrono::system_clock::now() - grad);
892 computeJointProperties(i);
893 state_is_in_collision_[i] =
false;
900 for (
size_t k = 0; k < info.sphere_locations.size(); ++k)
902 collision_point_pos_eigen_[i][j][0] = info.sphere_locations[k].x();
903 collision_point_pos_eigen_[i][j][1] = info.sphere_locations[k].y();
904 collision_point_pos_eigen_[i][j][2] = info.sphere_locations[k].z();
906 collision_point_potential_[i][j] =
907 getPotential(info.distances[k], info.sphere_radii[k], parameters_->
min_clearance_);
908 collision_point_potential_gradient_[i][j][0] = info.gradients[k].x();
909 collision_point_potential_gradient_[i][j][1] = info.gradients[k].y();
910 collision_point_potential_gradient_[i][j][2] = info.gradients[k].z();
912 point_is_in_collision_[i][j] = (info.distances[k] - info.sphere_radii[k] < info.sphere_radii[k]);
914 if (point_is_in_collision_[i][j])
916 state_is_in_collision_[i] =
true;
917 is_collision_free_ =
false;
926 for (
int i = free_vars_start_; i <= free_vars_end_; ++i)
928 for (
int j = 0; j < num_collision_points_; ++j)
930 collision_point_vel_eigen_[i][j] = Eigen::Vector3d(0, 0, 0);
931 collision_point_acc_eigen_[i][j] = Eigen::Vector3d(0, 0, 0);
932 for (
int k = -DIFF_RULE_LENGTH / 2; k <= DIFF_RULE_LENGTH / 2; ++k)
934 collision_point_vel_eigen_[i][j] +=
935 (inv_time * DIFF_RULES[0][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
936 collision_point_acc_eigen_[i][j] +=
937 (inv_time_sq * DIFF_RULES[1][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
941 collision_point_vel_mag_[i][j] = collision_point_vel_eigen_[i][j].norm();
946void ChompOptimizer::setRobotStateFromPoint(ChompTrajectory& group_trajectory,
int i)
948 const Eigen::MatrixXd::RowXpr& point = group_trajectory.getTrajectoryPoint(i);
950 std::vector<double> joint_states;
951 joint_states.reserve(group_trajectory.getNumJoints());
952 for (
size_t j = 0; j < group_trajectory.getNumJoints(); ++j)
953 joint_states.emplace_back(point(0, j));
959void ChompOptimizer::perturbTrajectory()
962 if (worst_collision_cost_state_ < 0)
964 int mid_point = worst_collision_cost_state_;
968 std::vector<double> vals;
970 double* ptr = &vals[0];
971 Eigen::Map<Eigen::VectorXd> random_matrix(ptr, vals.size());
979 joint_state_velocities_.normalize();
980 random_matrix = (Eigen::MatrixXd::Identity(num_joints_, num_joints_) -
981 joint_state_velocities_ * joint_state_velocities_.transpose()) *
984 int mp_free_vars_index = mid_point - free_vars_start_;
985 for (
int i = 0; i < num_joints_; ++i)
988 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 * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
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.
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
A link from the robot. Contains the constant transform applied to the link and its geometry.
const std::string & getName() const
The name of this link.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
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.
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 setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
void update(bool force=false)
Update all transforms.
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
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.
rclcpp::Logger getLogger()
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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.