48 #include <Eigen/StdVector>
80 return is_collision_free_;
84 inline double getPotential(
double field_distance,
double radius,
double clearance)
86 double d = field_distance - radius;
94 const double diff = (
d - clearance);
95 const double gradient_magnitude = diff / clearance;
96 return 0.5 * gradient_magnitude * diff;
100 return -
d + 0.5 * clearance;
103 template <
typename Derived>
104 void getJacobian(
int trajectoryPoint,
Eigen::Vector3d& collision_point_pos, std::string& jointName,
105 Eigen::MatrixBase<Derived>& jacobian)
const;
111 void setRobotStateFromPoint(ChompTrajectory& group_trajectory,
int i);
118 int num_collision_points_;
119 int free_vars_start_;
122 unsigned int collision_free_iteration_;
124 ChompTrajectory* full_trajectory_;
125 const moveit::core::RobotModelConstPtr& robot_model_;
126 std::string planning_group_;
127 const ChompParameters* parameters_;
128 ChompTrajectory group_trajectory_;
129 planning_scene::PlanningSceneConstPtr planning_scene_;
135 std::vector<ChompCost> joint_costs_;
136 collision_detection::GroupStateRepresentationPtr gsr_;
139 std::vector<std::vector<std::string> > collision_point_joint_names_;
140 std::vector<EigenSTL::vector_Vector3d> collision_point_pos_eigen_;
141 std::vector<EigenSTL::vector_Vector3d> collision_point_vel_eigen_;
142 std::vector<EigenSTL::vector_Vector3d> collision_point_acc_eigen_;
143 std::vector<std::vector<double> > collision_point_potential_;
144 std::vector<std::vector<double> > collision_point_vel_mag_;
145 std::vector<EigenSTL::vector_Vector3d> collision_point_potential_gradient_;
146 std::vector<EigenSTL::vector_Vector3d> joint_axes_;
147 std::vector<EigenSTL::vector_Vector3d> joint_positions_;
148 Eigen::MatrixXd group_trajectory_backup_;
149 Eigen::MatrixXd best_group_trajectory_;
150 double best_group_trajectory_cost_;
151 int last_improvement_iteration_;
152 unsigned int num_collision_free_iterations_;
155 Eigen::MatrixXd momentum_;
156 Eigen::MatrixXd random_momentum_;
157 Eigen::VectorXd random_joint_momentum_;
158 std::vector<MultivariateGaussian> multivariate_gaussian_;
159 double stochasticity_factor_;
161 std::vector<int> state_is_in_collision_;
163 std::vector<std::vector<int> > point_is_in_collision_;
164 bool is_collision_free_;
165 double worst_collision_cost_state_;
167 Eigen::MatrixXd smoothness_increments_;
168 Eigen::MatrixXd collision_increments_;
169 Eigen::MatrixXd final_increments_;
172 Eigen::VectorXd smoothness_derivative_;
173 Eigen::MatrixXd jacobian_;
174 Eigen::MatrixXd jacobian_pseudo_inverse_;
175 Eigen::MatrixXd jacobian_jacobian_tranpose_;
176 Eigen::VectorXd random_state_;
177 Eigen::VectorXd joint_state_velocities_;
179 std::vector<std::string> joint_names_;
180 std::map<std::string, std::map<std::string, bool> > joint_parent_map_;
182 inline bool isParent(
const std::string& childLink,
const std::string& parentLink)
const
184 if (childLink == parentLink)
189 if (joint_parent_map_.find(childLink) == joint_parent_map_.end())
194 const std::map<std::string, bool>& parents = joint_parent_map_.at(childLink);
195 return (parents.find(parentLink) != parents.end() && parents.at(parentLink));
200 void calculateSmoothnessIncrements();
201 void calculateCollisionIncrements();
202 void calculateTotalIncrements();
203 void performForwardKinematics();
204 void addIncrementsToTrajectory();
205 void updateFullTrajectory();
207 void handleJointLimits();
208 double getTrajectoryCost();
209 double getSmoothnessCost();
210 double getCollisionCost();
211 void perturbTrajectory();
212 void getRandomMomentum();
213 void updateMomentum();
214 void updatePositionFromMomentum();
215 void calculatePseudoInverse();
216 void computeJointProperties(
int trajectoryPoint);
217 bool isCurrentTrajectoryMeshToMeshCollisionFree()
const;
bool isCollisionFree() const
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()
bool isInitialized() const
Represents a discretized joint-space trajectory for CHOMP.
This hybrid collision environment combines FCL and a distance field. Both can be used to calculate co...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Vec3fX< details::Vec3Data< double > > Vector3d
This namespace includes the central class for representing planning contexts.