Assigns a cost value to each robot state by evaluating the minimum distance between the robot and the nearest obstacle.
More...
#include <obstacle_distance_gradient.h>
|
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)=0 |
| computes the state costs as a function of the parameters for each time step. More...
|
|
virtual bool | configure (const XmlRpc::XmlRpcValue &config)=0 |
| 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) |
| Called by the Stomp Task at the end of the optimization process. More...
|
|
virtual std::string | getGroupName () const |
|
virtual std::string | getName () const |
|
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 bool | initialize (moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, XmlRpc::XmlRpcValue &config)=0 |
| Initializes and configures the Cost Function. More...
|
|
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...
|
|
virtual bool | setMotionPlanRequest (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code)=0 |
| Stores the planning details which will be used during the costs calculations. More...
|
|
Assigns a cost value to each robot state by evaluating the minimum distance between the robot and the nearest obstacle.
The interface class for the STOMP cost functions.
- Examples:
- All examples are located here STOMP MoveIt! examples
Definition at line 53 of file stomp_cost_function.h.
virtual bool stomp_moveit::cost_functions::StompCostFunction::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 |
|
) |
| |
|
pure virtual |
computes the state costs as a function of the parameters for each time step.
- 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.
Implemented in stomp_moveit::cost_functions::CollisionCheck, and stomp_moveit::cost_functions::ObstacleDistanceGradient.
virtual bool stomp_moveit::cost_functions::StompCostFunction::configure |
( |
const XmlRpc::XmlRpcValue & |
config | ) |
|
|
pure virtual |
virtual void stomp_moveit::cost_functions::StompCostFunction::done |
( |
bool |
success, |
|
|
int |
total_iterations, |
|
|
double |
final_cost, |
|
|
const Eigen::MatrixXd & |
parameters |
|
) |
| |
|
inlinevirtual |
virtual bool stomp_moveit::cost_functions::StompCostFunction::initialize |
( |
moveit::core::RobotModelConstPtr |
robot_model_ptr, |
|
|
const std::string & |
group_name, |
|
|
XmlRpc::XmlRpcValue & |
config |
|
) |
| |
|
pure virtual |
virtual void stomp_moveit::cost_functions::StompCostFunction::postIteration |
( |
std::size_t |
start_timestep, |
|
|
std::size_t |
num_timesteps, |
|
|
int |
iteration_number, |
|
|
double |
cost, |
|
|
const Eigen::MatrixXd & |
parameters |
|
) |
| |
|
inlinevirtual |
Called by STOMP at the end of each iteration.
- Parameters
-
start_timestep | The start index into the 'parameters' array, usually 0. |
num_timesteps | The number of elements to use from 'parameters' starting from 'start_timestep' |
iteration_number | The current iteration count in the optimization loop |
cost | The cost value for the current parameters. |
parameters | The value of the parameters at the end of the current iteration [num_dimensions x num_timesteps]. |
Definition at line 122 of file stomp_cost_function.h.
The documentation for this class was generated from the following file: