|
virtual bool | computeCosts (const Eigen::MatrixXd ¶meters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::VectorXd &costs, bool &validity) override |
| computes the state costs by calculating the minimum distance between the robot and an obstacle. More...
|
|
virtual bool | configure (const XmlRpc::XmlRpcValue &config) override |
| Sets internal members of the plugin from the configuration data. More...
|
|
virtual void | done (bool success, int total_iterations, double final_cost, const Eigen::MatrixXd ¶meters) override |
| Called by the Stomp Task at the end of the optimization process. More...
|
|
virtual std::string | getGroupName () const override |
|
virtual std::string | getName () const override |
|
virtual bool | initialize (moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, XmlRpc::XmlRpcValue &config) override |
| Initializes and configures the Cost Function. Calls the configure method and passes the 'config' value. More...
|
|
virtual bool | setMotionPlanRequest (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code) override |
| Stores the planning details which will be used during the costs calculations. More...
|
|
virtual int | getOptimizedIndex () const |
| The index returned by this method will be passed by the Task to the corresponding plugin method as the 'rollout_number' argument when operating on the noiseless (optimized) parameters.
|
|
virtual double | getWeight () const |
|
virtual void | postIteration (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, double cost, const Eigen::MatrixXd ¶meters) |
| Called by STOMP at the end of each iteration. More...
|
|
|
bool | checkIntermediateCollisions (const Eigen::VectorXd &start, const Eigen::VectorXd &end, double longest_valid_joint_move) |
| Checks for collision between consecutive points by dividing the joint move into sub-moves where the maximum joint motion can not exceed the longest_valid_joint_move value. More...
|
|
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::checkIntermediateCollisions |
( |
const Eigen::VectorXd & |
start, |
|
|
const Eigen::VectorXd & |
end, |
|
|
double |
longest_valid_joint_move |
|
) |
| |
|
protected |
Checks for collision between consecutive points by dividing the joint move into sub-moves where the maximum joint motion can not exceed the longest_valid_joint_move value.
- Parameters
-
start | The start joint pose |
end | The end joint pose |
longest_valid_joint_move | The maximum distance that the joints are allowed to move before checking for collisions. |
- Returns
- True if the interval is collision free, false otherwise.
Definition at line 209 of file obstacle_distance_gradient.cpp.
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::computeCosts |
( |
const Eigen::MatrixXd & |
parameters, |
|
|
std::size_t |
start_timestep, |
|
|
std::size_t |
num_timesteps, |
|
|
int |
iteration_number, |
|
|
int |
rollout_number, |
|
|
Eigen::VectorXd & |
costs, |
|
|
bool & |
validity |
|
) |
| |
|
overridevirtual |
computes the state costs by calculating the minimum distance between the robot and an obstacle.
- Parameters
-
parameters | The parameter values to evaluate for state costs [num_dimensions x num_parameters] |
start_timestep | start index into the 'parameters' array, usually 0. |
num_timesteps | number of elements to use from 'parameters' starting from 'start_timestep' * |
iteration_number | The current iteration count in the optimization loop |
rollout_number | index of the noisy trajectory whose cost is being evaluated. * |
costs | vector containing the state costs per timestep. |
validity | whether or not the trajectory is valid |
- Returns
- false if there was an irrecoverable failure, true otherwise.
Implements stomp_moveit::cost_functions::StompCostFunction.
Definition at line 131 of file obstacle_distance_gradient.cpp.
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::configure |
( |
const XmlRpc::XmlRpcValue & |
config | ) |
|
|
overridevirtual |
void stomp_moveit::cost_functions::ObstacleDistanceGradient::done |
( |
bool |
success, |
|
|
int |
total_iterations, |
|
|
double |
final_cost, |
|
|
const Eigen::MatrixXd & |
parameters |
|
) |
| |
|
overridevirtual |
Called by the Stomp Task at the end of the optimization process.
- Parameters
-
success | Whether the optimization succeeded |
total_iterations | Number of iterations used |
final_cost | The cost value after optimizing. |
parameters | The parameters generated at the end of current iteration [num_dimensions x num_timesteps] |
Reimplemented from stomp_moveit::cost_functions::StompCostFunction.
Definition at line 255 of file obstacle_distance_gradient.cpp.
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::initialize |
( |
moveit::core::RobotModelConstPtr |
robot_model_ptr, |
|
|
const std::string & |
group_name, |
|
|
XmlRpc::XmlRpcValue & |
config |
|
) |
| |
|
overridevirtual |
Initializes and configures the Cost Function. Calls the configure method and passes the 'config' value.
- Parameters
-
robot_model_ptr | A pointer to the robot model. |
group_name | The designated planning group. |
config | The configuration data. Usually loaded from the ros parameter server |
- Returns
- true if succeeded, false otherwise.
Implements stomp_moveit::cost_functions::StompCostFunction.
Definition at line 52 of file obstacle_distance_gradient.cpp.
The documentation for this class was generated from the following files: