Go to the documentation of this file.
39 #include <visualization_msgs/MarkerArray.h>
44 #include <eigen3/Eigen/LU>
45 #include <eigen3/Eigen/Core>
52 std::default_random_engine seed;
53 std::uniform_real_distribution<> uniform(0.0, 1.0);
58 const std::string& planning_group,
const ChompParameters* parameters,
60 : full_trajectory_(trajectory)
62 , planning_group_(planning_group)
63 , parameters_(parameters)
67 , start_state_(start_state)
70 std::vector<std::string> cd_names;
73 ROS_INFO_STREAM(
"The following collision detectors are available in the planning scene.");
74 for (
const std::string& cd_name : cd_names)
85 ROS_WARN_STREAM(
"Could not initialize hybrid collision world from planning scene");
117 double max_cost_scale = 0.0;
122 for (
size_t i = 0; i < joint_models.size(); i++)
124 double joint_cost = 1.0;
126 std::vector<double> derivative_costs(3);
131 double cost_scale =
joint_costs_[i].getMaxQuadCostInvValue();
132 if (max_cost_scale < cost_scale)
133 max_cost_scale = cost_scale;
189 std::map<std::string, std::string> fixed_link_resolution_map;
200 if (!jm->getParentLinkModel())
203 fixed_link_resolution_map[jm->getName()] = jm->getParentLinkModel()->getParentJointModel()->getName();
209 if (fixed_link_resolution_map.find(link->getParentJointModel()->getName()) == fixed_link_resolution_map.end())
221 fixed_link_resolution_map[link->getParentJointModel()->getName()] = parent_model->
getName();
227 for (
int i = start; i <= end; ++i)
234 if (fixed_link_resolution_map.find(info.
joint_name) != fixed_link_resolution_map.end())
257 bool found_root =
false;
264 if (parent_model ==
nullptr)
295 bool optimization_result = 0;
299 int cost_window = 10;
300 std::vector<double> costs(cost_window, 0.0);
302 bool should_break_out =
false;
312 double cost = c_cost + s_cost;
378 ROS_INFO(
"Chomp Got mesh to mesh safety at iter %d. Breaking out early.",
iteration_);
381 should_break_out =
true;
412 if (c_cost < parameters_->collision_threshold_)
417 should_break_out =
true;
427 ROS_WARN(
"Breaking out early due to time limit constraints.");
480 if (should_break_out)
501 optimization_result =
true;
502 ROS_INFO(
"Chomp path is collision free");
506 optimization_result =
false;
507 ROS_ERROR(
"Chomp path is not collision free!");
517 return optimization_result;
522 moveit_msgs::RobotTrajectory traj;
527 trajectory_msgs::JointTrajectoryPoint
point;
532 traj.joint_trajectory.points.push_back(
point);
534 moveit_msgs::RobotState start_state_msg;
587 Eigen::Vector3d potential_gradient;
588 Eigen::Vector3d normalized_velocity;
589 Eigen::Matrix3d orthogonal_projector;
590 Eigen::Vector3d curvature_vector;
591 Eigen::Vector3d cartesian_gradient;
607 end_point = start_point;
614 for (
int i = start_point; i <= end_point; i++)
620 if (potential < 0.0001)
626 vel_mag_sq = vel_mag * vel_mag;
631 orthogonal_projector = Eigen::Matrix3d::Identity() - (normalized_velocity * normalized_velocity.transpose());
633 cartesian_gradient = vel_mag * (orthogonal_projector * potential_gradient - potential * curvature_vector);
680 for (
size_t i = 0; i < joint_models.size(); i++)
687 if (max_scale < scale)
689 if (min_scale < scale)
707 std::cout <<
"Cost = " << cost << std::endl;
717 double smoothness_cost = 0.0;
727 double collision_cost = 0.0;
729 double worst_collision_cost = 0.0;
735 double state_collision_cost = 0.0;
740 collision_cost += state_collision_cost;
741 if (state_collision_cost > worst_collision_cost)
743 worst_collision_cost = state_collision_cost;
764 (
robot_model_->getLinkModel(child_link_name)->getJointOriginTransform() *
768 Eigen::Vector3d axis;
770 if (revolute_joint !=
nullptr)
772 axis = revolute_joint->
getAxis();
774 else if (prismatic_joint !=
nullptr)
776 axis = prismatic_joint->
getAxis();
780 axis = Eigen::Vector3d::Identity();
783 axis = joint_transform * axis;
790 template <
typename Derived>
792 Eigen::MatrixBase<Derived>& jacobian)
const
798 Eigen::Vector3d column =
joint_axes_[trajectory_point][j].cross(
799 Eigen::Vector3d(collision_point_pos(0), collision_point_pos(1), collision_point_pos(2)) -
802 jacobian.col(j)[0] = column.x();
803 jacobian.col(j)[1] = column.y();
804 jacobian.col(j)[2] = column.z();
808 jacobian.col(j)[0] = 0.0;
809 jacobian.col(j)[1] = 0.0;
810 jacobian.col(j)[2] = 0.0;
818 for (
size_t joint_i = 0; joint_i < joint_models.size(); joint_i++)
834 double joint_max = -DBL_MAX;
835 double joint_min = DBL_MAX;
839 if (
bound.min_position_ < joint_min)
841 joint_min =
bound.min_position_;
844 if (
bound.max_position_ > joint_max)
846 joint_max =
bound.max_position_;
852 bool violation =
false;
855 double max_abs_violation = 1e-6;
856 double max_violation = 0.0;
857 int max_violation_index = 0;
862 double absolute_amount = 0.0;
866 absolute_amount = fabs(amount);
871 absolute_amount = fabs(amount);
873 if (absolute_amount > max_abs_violation)
875 max_abs_violation = absolute_amount;
876 max_violation = amount;
877 max_violation_index = i;
886 max_violation /
joint_costs_[joint_i].getQuadraticCostInverse()(free_var_index, free_var_index);
888 multiplier *
joint_costs_[joint_i].getQuadraticCostInverse().col(free_var_index);
899 double inv_time_sq = inv_time * inv_time;
915 for (
int i = start; i <= end; ++i)
994 const Eigen::MatrixXd::RowXpr&
point = group_trajectory.getTrajectoryPoint(i);
996 std::vector<double> joint_states;
997 joint_states.reserve(group_trajectory.getNumJoints());
998 for (
size_t j = 0; j < group_trajectory.getNumJoints(); j++)
999 joint_states.emplace_back(
point(0, j));
1014 std::vector<double> vals;
1016 double* ptr = &vals[0];
1017 Eigen::Map<Eigen::VectorXd> random_matrix(ptr, vals.size());
int max_iterations_after_collision_free_
double planning_time_limit_
unsigned int num_collision_free_iterations_
const std::vector< const JointModel * > & getActiveJointModels() const
Eigen::VectorXd random_state_
Eigen::MatrixXd jacobian_pseudo_inverse_
std::string planning_group_
void getJacobian(int trajectoryPoint, Eigen::Vector3d &collision_point_pos, std::string &jointName, Eigen::MatrixBase< Derived > &jacobian) const
const ChompParameters * parameters_
static const double DIFF_RULES[3][DIFF_RULE_LENGTH]
bool initialize(MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup)
void addIncrementsToTrajectory()
std::vector< MultivariateGaussian > multivariate_gaussian_
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
void setRobotStateFromPoint(ChompTrajectory &group_trajectory, int i)
unsigned int collision_free_iteration_
collision_detection::GroupStateRepresentationPtr gsr_
std::vector< std::vector< std::string > > collision_point_joint_names_
const moveit::core::JointModelGroup * joint_model_group_
const JointModel * getJointModel(const std::string &joint) const
std::vector< EigenSTL::vector_Vector3d > collision_point_acc_eigen_
EigenSTL::vector_Vector3d gradients
#define ROS_ERROR_STREAM(args)
double smoothness_cost_velocity_
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
Eigen::MatrixXd best_group_trajectory_
std::vector< EigenSTL::vector_Vector3d > collision_point_potential_gradient_
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
int num_collision_points_
bool isCurrentTrajectoryMeshToMeshCollisionFree() const
double getDiscretization() const
Gets the discretization time interval of the trajectory.
Eigen::MatrixXd smoothness_increments_
double getPotential(double field_distance, double radius, double clearance)
void calculateSmoothnessIncrements()
double pseudo_inverse_ridge_factor_
enable pseudo inverse calculations or not.
std::vector< double > sphere_radii
Eigen::MatrixXd jacobian_jacobian_tranpose_
std::map< std::string, std::map< std::string, bool > > joint_parent_map_
std::vector< EigenSTL::vector_Vector3d > collision_point_vel_eigen_
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
const std::string & getName() const
void setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
const JointModel * getParentJointModel() const
Represents the smoothness cost for CHOMP, for a single joint.
std::vector< EigenSTL::vector_Vector3d > joint_axes_
planning_scene::PlanningSceneConstPtr planning_scene_
std::vector< std::string > joint_names_
ChompTrajectory group_trajectory_
const collision_detection::CollisionEnvHybrid * hy_env_
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeJointTrajectoryBlock(size_t joint)
Gets the block of free (optimizable) trajectory for a single joint.
double best_group_trajectory_cost_
std::vector< int > state_is_in_collision_
int last_improvement_iteration_
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
void calculateCollisionIncrements()
void setToRandomPositions()
ChompOptimizer(ChompTrajectory *trajectory, const planning_scene::PlanningSceneConstPtr &planning_scene, const std::string &planning_group, const ChompParameters *parameters, const moveit::core::RobotState &start_state)
#define ROS_DEBUG_STREAM(args)
double getCollisionCost()
bool isContinuous() const
void getJointVelocities(size_t traj_point, Eigen::MatrixBase< Derived > &velocities)
Gets the joint velocities at the given trajectory point.
bool isParent(const std::string &childLink, const std::string &parentLink) const
JointType getType() const
const moveit::core::RobotModelConstPtr & robot_model_
const LinkModel * getChildLinkModel() const
ChompTrajectory * full_trajectory_
#define ROS_WARN_STREAM(args)
double getTrajectoryCost()
double obstacle_cost_weight_
const LinkModel * getParentLinkModel() const
const Eigen::Vector3d & getAxis() const
double smoothness_cost_jerk_
variables associated with the cost in acceleration
double joint_update_limit_
set the ridge factor if pseudo inverse is enabled
size_t getStartIndex() const
Gets the start index.
Eigen::MatrixXd collision_increments_
Eigen::MatrixXd::ColXpr getJointTrajectory(int joint)
void update(bool force=false)
std::vector< EigenSTL::vector_Vector3d > collision_point_pos_eigen_
const VariableBounds & getVariableBounds(const std::string &variable) const
std::vector< std::vector< double > > collision_point_potential_
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
std::vector< VariableBounds > Bounds
template Interval< double > bound(const Interval< double > &i, const Interval< double > &other)
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
void calculateTotalIncrements()
const std::vector< const JointModel * > & getFixedJointModels() const
bool filter_mode_
the collision threshold cost that needs to be mainted to avoid collisions
std::vector< std::vector< int > > point_is_in_collision_
void performForwardKinematics()
EigenSTL::vector_Vector3d sphere_locations
bool use_pseudo_inverse_
the noise added to the diagnal of the total quadratic cost matrix in the objective function
double smoothness_cost_weight_
size_t getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
#define ROS_INFO_STREAM(args)
moveit::core::RobotState state_
size_t getEndIndex() const
Gets the end index.
std::chrono::system_clock::time_point point
int max_iterations_
maximum time the optimizer can take to find a solution before terminating
static const int DIFF_RULE_LENGTH
bool use_stochastic_descent_
variables associated with the cost in jerk
size_t getNumPoints() const
Gets the number of points in the trajectory.
Eigen::MatrixXd jacobian_
Eigen::MatrixXd group_trajectory_backup_
double worst_collision_cost_state_
void updateFullTrajectory()
void registerParents(const moveit::core::JointModel *model)
const std::vector< const LinkModel * > & getUpdatedLinkModels() const
std::vector< EigenSTL::vector_Vector3d > joint_positions_
moveit::core::RobotState start_state_
void computeJointProperties(int trajectoryPoint)
double min_clearance_
set the update limit for the robot joints
Eigen::VectorXd smoothness_derivative_
Eigen::MatrixXd final_increments_
const std::string & getName() const
double stochasticity_factor_
const JointModelGroup * getJointModelGroup(const std::string &group) const
const Eigen::Vector3d & getAxis() const
void calculatePseudoInverse()
Eigen::VectorXd joint_state_velocities_
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.
double smoothness_cost_acceleration_
variables associated with the cost in velocity
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
double getSmoothnessCost()
virtual ~ChompOptimizer()
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
std::vector< double > distances
std::vector< ChompCost > joint_costs_
std::vector< std::vector< double > > collision_point_vel_mag_
chomp_motion_planner
Author(s): Gil Jones
, Mrinal Kalakrishnan
autogenerated on Sat Mar 15 2025 02:26:05