#include <chomp_optimizer.h>
Public Member Functions | |
ChompOptimizer (ChompTrajectory *trajectory, const planning_scene::PlanningSceneConstPtr &planning_scene, const std::string &planning_group, const ChompParameters *parameters, const moveit::core::RobotState &start_state) | |
void | destroy () |
bool | isCollisionFree () const |
bool | isInitialized () const |
bool | optimize () |
virtual | ~ChompOptimizer () |
Private Member Functions | |
void | addIncrementsToTrajectory () |
void | calculateCollisionIncrements () |
void | calculatePseudoInverse () |
void | calculateSmoothnessIncrements () |
void | calculateTotalIncrements () |
void | computeJointProperties (int trajectoryPoint) |
void | debugCost () |
double | getCollisionCost () |
template<typename Derived > | |
void | getJacobian (int trajectoryPoint, Eigen::Vector3d &collision_point_pos, std::string &jointName, Eigen::MatrixBase< Derived > &jacobian) const |
double | getPotential (double field_distance, double radius, double clearence) |
void | getRandomMomentum () |
double | getSmoothnessCost () |
double | getTrajectoryCost () |
void | handleJointLimits () |
void | initialize () |
bool | isCurrentTrajectoryMeshToMeshCollisionFree () const |
bool | isParent (const std::string &childLink, const std::string &parentLink) const |
void | performForwardKinematics () |
void | perturbTrajectory () |
void | registerParents (const moveit::core::JointModel *model) |
void | setRobotStateFromPoint (ChompTrajectory &group_trajectory, int i) |
void | updateFullTrajectory () |
void | updateMomentum () |
void | updatePositionFromMomentum () |
Definition at line 55 of file chomp_optimizer.h.
chomp::ChompOptimizer::ChompOptimizer | ( | ChompTrajectory * | trajectory, |
const planning_scene::PlanningSceneConstPtr & | planning_scene, | ||
const std::string & | planning_group, | ||
const ChompParameters * | parameters, | ||
const moveit::core::RobotState & | start_state | ||
) |
Definition at line 54 of file chomp_optimizer.cpp.
|
virtual |
Definition at line 272 of file chomp_optimizer.cpp.
|
private |
Definition at line 702 of file chomp_optimizer.cpp.
|
private |
Definition at line 607 of file chomp_optimizer.cpp.
|
private |
Definition at line 684 of file chomp_optimizer.cpp.
|
private |
TODO: HMC BASED COMMENTED CODE BELOW, Need to uncomment and perform extensive testing by varying the HMC parameters values in the chomp_planning.yaml file so that CHOMP can find optimal paths
Definition at line 598 of file chomp_optimizer.cpp.
|
private |
Definition at line 691 of file chomp_optimizer.cpp.
|
private |
Definition at line 776 of file chomp_optimizer.cpp.
|
private |
Definition at line 727 of file chomp_optimizer.cpp.
|
inline |
Definition at line 70 of file chomp_optimizer.h.
|
private |
Definition at line 750 of file chomp_optimizer.cpp.
|
private |
Definition at line 817 of file chomp_optimizer.cpp.
|
inlineprivate |
Definition at line 86 of file chomp_optimizer.h.
|
private |
|
private |
Definition at line 740 of file chomp_optimizer.cpp.
|
private |
Definition at line 735 of file chomp_optimizer.cpp.
|
private |
Definition at line 841 of file chomp_optimizer.cpp.
|
private |
TODO: HMC BASED COMMENTED CODE BELOW, Need to uncomment and perform extensive testing by varying the HMC parameters values in the chomp_planning.yaml file so that CHOMP can find optimal paths
Definition at line 96 of file chomp_optimizer.cpp.
|
inline |
Definition at line 80 of file chomp_optimizer.h.
|
private |
Definition at line 545 of file chomp_optimizer.cpp.
|
inline |
Definition at line 75 of file chomp_optimizer.h.
|
inlineprivate |
Definition at line 189 of file chomp_optimizer.h.
bool chomp::ChompOptimizer::optimize | ( | ) |
Optimizes the CHOMP cost function and tries to find an optimal path
TODO: HMC BASED COMMENTED CODE BELOW, Need to uncomment and perform extensive testing by varying the HMC parameters values in the chomp_planning.yaml file so that CHOMP can find optimal paths
TODO: HMC BASED COMMENTED CODE BELOW, Need to uncomment and perform extensive testing by varying the HMC parameters values in the chomp_planning.yaml file so that CHOMP can find optimal paths
TODO: HMC BASED COMMENTED CODE BELOW, Need to uncomment and perform extensive testing by varying the HMC parameters values in the chomp_planning.yaml file so that CHOMP can find optimal paths
TODO: HMC BASED COMMENTED CODE BELOW, Need to uncomment and perform extensive testing by varying the HMC parameters values in the chomp_planning.yaml file so that CHOMP can find optimal paths
Definition at line 316 of file chomp_optimizer.cpp.
|
private |
Definition at line 922 of file chomp_optimizer.cpp.
|
private |
Definition at line 1034 of file chomp_optimizer.cpp.
|
private |
Definition at line 277 of file chomp_optimizer.cpp.
|
private |
Definition at line 1020 of file chomp_optimizer.cpp.
|
private |
Definition at line 722 of file chomp_optimizer.cpp.
|
private |
|
private |
|
private |
Definition at line 156 of file chomp_optimizer.h.
|
private |
Definition at line 157 of file chomp_optimizer.h.
|
private |
Definition at line 128 of file chomp_optimizer.h.
|
private |
Definition at line 175 of file chomp_optimizer.h.
|
private |
Definition at line 149 of file chomp_optimizer.h.
|
private |
Definition at line 146 of file chomp_optimizer.h.
|
private |
Definition at line 147 of file chomp_optimizer.h.
|
private |
Definition at line 150 of file chomp_optimizer.h.
|
private |
Definition at line 152 of file chomp_optimizer.h.
|
private |
Definition at line 148 of file chomp_optimizer.h.
|
private |
Definition at line 151 of file chomp_optimizer.h.
|
private |
Definition at line 176 of file chomp_optimizer.h.
|
private |
Definition at line 126 of file chomp_optimizer.h.
|
private |
Definition at line 125 of file chomp_optimizer.h.
|
private |
Definition at line 130 of file chomp_optimizer.h.
|
private |
Definition at line 134 of file chomp_optimizer.h.
|
private |
Definition at line 155 of file chomp_optimizer.h.
|
private |
Definition at line 143 of file chomp_optimizer.h.
|
private |
Definition at line 140 of file chomp_optimizer.h.
|
private |
Definition at line 139 of file chomp_optimizer.h.
|
private |
Definition at line 144 of file chomp_optimizer.h.
|
private |
Definition at line 171 of file chomp_optimizer.h.
|
private |
Definition at line 127 of file chomp_optimizer.h.
|
private |
Definition at line 180 of file chomp_optimizer.h.
|
private |
Definition at line 182 of file chomp_optimizer.h.
|
private |
Definition at line 181 of file chomp_optimizer.h.
|
private |
Definition at line 153 of file chomp_optimizer.h.
|
private |
Definition at line 142 of file chomp_optimizer.h.
|
private |
Definition at line 138 of file chomp_optimizer.h.
|
private |
Definition at line 186 of file chomp_optimizer.h.
|
private |
Definition at line 187 of file chomp_optimizer.h.
|
private |
Definition at line 154 of file chomp_optimizer.h.
|
private |
Definition at line 184 of file chomp_optimizer.h.
|
private |
Definition at line 131 of file chomp_optimizer.h.
|
private |
Definition at line 158 of file chomp_optimizer.h.
|
private |
Definition at line 162 of file chomp_optimizer.h.
|
private |
Definition at line 165 of file chomp_optimizer.h.
|
private |
Definition at line 159 of file chomp_optimizer.h.
|
private |
Definition at line 124 of file chomp_optimizer.h.
|
private |
Definition at line 121 of file chomp_optimizer.h.
|
private |
Definition at line 123 of file chomp_optimizer.h.
|
private |
Definition at line 122 of file chomp_optimizer.h.
|
private |
Definition at line 133 of file chomp_optimizer.h.
|
private |
Definition at line 132 of file chomp_optimizer.h.
|
private |
Definition at line 135 of file chomp_optimizer.h.
|
private |
Definition at line 170 of file chomp_optimizer.h.
|
private |
Definition at line 164 of file chomp_optimizer.h.
|
private |
Definition at line 163 of file chomp_optimizer.h.
|
private |
Definition at line 183 of file chomp_optimizer.h.
|
private |
Definition at line 179 of file chomp_optimizer.h.
|
private |
Definition at line 174 of file chomp_optimizer.h.
|
private |
Definition at line 137 of file chomp_optimizer.h.
|
private |
Definition at line 136 of file chomp_optimizer.h.
|
private |
Array containing a boolean about collision info for each point in the trajectory
Definition at line 168 of file chomp_optimizer.h.
|
private |
Definition at line 166 of file chomp_optimizer.h.
|
private |
Definition at line 172 of file chomp_optimizer.h.