37 #ifndef CHOMP_OPTIMIZER_H_ 38 #define CHOMP_OPTIMIZER_H_ 50 #include <Eigen/StdVector> 86 inline double getPotential(
double field_distance,
double radius,
double clearence)
88 double d = field_distance - radius;
89 double potential = 0.0;
98 double diff = (d - clearence);
99 double gradient_magnitude = diff * clearence;
100 potential = 0.5 * gradient_magnitude * diff;
104 potential = -d + 0.5 * clearence;
109 template <
typename Derived>
110 void getJacobian(
int trajectoryPoint, Eigen::Vector3d& collision_point_pos, std::string& jointName,
111 Eigen::MatrixBase<Derived>& jacobian)
const;
131 const moveit::core::RobotModelConstPtr&
kmodel_;
143 collision_detection::GroupStateRepresentationPtr
gsr_;
189 inline bool isParent(
const std::string& childLink,
const std::string& parentLink)
const 191 if (childLink == parentLink)
196 if (joint_parent_map_.find(childLink) == joint_parent_map_.end())
201 const std::map<std::string, bool>& parents = joint_parent_map_.at(childLink);
202 return (parents.find(parentLink) != parents.end() && parents.at(parentLink));
int num_collision_points_
const ChompParameters * parameters_
void addIncrementsToTrajectory()
double stochasticity_factor_
void calculateSmoothnessIncrements()
void getJacobian(int trajectoryPoint, Eigen::Vector3d &collision_point_pos, std::string &jointName, Eigen::MatrixBase< Derived > &jacobian) const
std::map< std::string, std::map< std::string, bool > > joint_parent_map_
unsigned int num_collision_free_iterations_
bool isInitialized() const
Eigen::MatrixXd jacobian_pseudo_inverse_
double getSmoothnessCost()
std::vector< EigenSTL::vector_Vector3d > collision_point_potential_gradient_
ChompTrajectory group_trajectory_
std::vector< std::string > joint_names_
std::vector< MultivariateGaussian > multivariate_gaussian_
const collision_detection::CollisionWorldHybrid * hy_world_
Eigen::MatrixXd smoothness_increments_
void calculateCollisionIncrements()
collision_detection::GroupStateRepresentationPtr gsr_
unsigned int collision_free_iteration_
const moveit::core::JointModelGroup * joint_model_group_
std::vector< EigenSTL::vector_Vector3d > collision_point_acc_eigen_
std::vector< std::vector< double > > collision_point_vel_mag_
ChompOptimizer(ChompTrajectory *trajectory, const planning_scene::PlanningSceneConstPtr &planning_scene, const std::string &planning_group, const ChompParameters *parameters, const moveit::core::RobotState &start_state)
const moveit::core::RobotModelConstPtr & kmodel_
std::vector< EigenSTL::vector_Vector3d > joint_axes_
planning_scene::PlanningSceneConstPtr planning_scene_
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
double getPotential(double field_distance, double radius, double clearence)
void setRobotStateFromPoint(ChompTrajectory &group_trajectory, int i)
ChompTrajectory * full_trajectory_
Eigen::VectorXd random_joint_momentum_
std::vector< std::vector< std::string > > collision_point_joint_names_
Eigen::MatrixXd jacobian_jacobian_tranpose_
bool isCurrentTrajectoryMeshToMeshCollisionFree() const
double getTrajectoryCost()
Eigen::MatrixXd best_group_trajectory_
const collision_detection::CollisionRobotHybrid * hy_robot_
void updatePositionFromMomentum()
std::vector< EigenSTL::vector_Vector3d > collision_point_vel_eigen_
bool isParent(const std::string &childLink, const std::string &parentLink) const
Eigen::MatrixXd random_momentum_
std::vector< EigenSTL::vector_Vector3d > collision_point_pos_eigen_
double best_group_trajectory_cost_
std::vector< int > state_is_in_collision_
int last_improvement_iteration_
double getCollisionCost()
Eigen::MatrixXd group_trajectory_backup_
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
void calculateTotalIncrements()
Eigen::MatrixXd collision_increments_
moveit::core::RobotState state_
std::vector< std::vector< double > > collision_point_potential_
Eigen::MatrixXd jacobian_
bool isCollisionFree() const
double worst_collision_cost_state_
void updateFullTrajectory()
Represents a discretized joint-space trajectory for CHOMP.
moveit::core::RobotState start_state_
std::vector< std::vector< int > > point_is_in_collision_
void performForwardKinematics()
std::vector< EigenSTL::vector_Vector3d > joint_positions_
virtual ~ChompOptimizer()
std::vector< ChompCost > joint_costs_
void calculatePseudoInverse()
void computeJointProperties(int trajectoryPoint)
void registerParents(const moveit::core::JointModel *model)
Eigen::VectorXd smoothness_derivative_
Eigen::MatrixXd final_increments_
Eigen::VectorXd joint_state_velocities_
Eigen::MatrixXd momentum_
Eigen::VectorXd random_state_
std::string planning_group_