Assigns a cost value to each robot state by evaluating the minimum distance between the robot and the nearest obstacle. More...
#include <stomp_cost_function.h>
Public Member Functions | |
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. | |
virtual bool | configure (const XmlRpc::XmlRpcValue &config)=0 |
Sets internal members of the plugin from the configuration data. | |
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. | |
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. | |
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. | |
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. | |
StompCostFunction () | |
virtual | ~StompCostFunction () |
Protected Attributes | |
double | cost_weight_ |
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.
Definition at line 53 of file stomp_cost_function.h.
Definition at line 56 of file stomp_cost_function.h.
virtual stomp_moveit::cost_functions::StompCostFunction::~StompCostFunction | ( | ) | [inline, virtual] |
Definition at line 62 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 | 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 |
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] |
Sets internal members of the plugin from the configuration data.
config | The configuration data . Usually loaded from the ros parameter server |
Implemented in stomp_moveit::cost_functions::CollisionCheck, and stomp_moveit::cost_functions::ObstacleDistanceGradient.
virtual void stomp_moveit::cost_functions::StompCostFunction::done | ( | bool | success, |
int | total_iterations, | ||
double | final_cost, | ||
const Eigen::MatrixXd & | parameters | ||
) | [inline, virtual] |
Called by the Stomp Task at the end of the optimization process.
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 in stomp_moveit::cost_functions::CollisionCheck, and stomp_moveit::cost_functions::ObstacleDistanceGradient.
Definition at line 133 of file stomp_cost_function.h.
virtual std::string stomp_moveit::cost_functions::StompCostFunction::getGroupName | ( | ) | const [inline, virtual] |
Reimplemented in stomp_moveit::cost_functions::CollisionCheck, and stomp_moveit::cost_functions::ObstacleDistanceGradient.
Definition at line 136 of file stomp_cost_function.h.
virtual std::string stomp_moveit::cost_functions::StompCostFunction::getName | ( | ) | const [inline, virtual] |
Reimplemented in stomp_moveit::cost_functions::CollisionCheck, and stomp_moveit::cost_functions::ObstacleDistanceGradient.
Definition at line 146 of file stomp_cost_function.h.
virtual int stomp_moveit::cost_functions::StompCostFunction::getOptimizedIndex | ( | ) | const [inline, virtual] |
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.
Definition at line 156 of file stomp_cost_function.h.
virtual double stomp_moveit::cost_functions::StompCostFunction::getWeight | ( | ) | const [inline, virtual] |
Definition at line 141 of file stomp_cost_function.h.
virtual bool stomp_moveit::cost_functions::StompCostFunction::initialize | ( | moveit::core::RobotModelConstPtr | robot_model_ptr, |
const std::string & | group_name, | ||
XmlRpc::XmlRpcValue & | config | ||
) | [pure virtual] |
Initializes and configures the Cost Function.
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 |
Implemented in stomp_moveit::cost_functions::CollisionCheck, and stomp_moveit::cost_functions::ObstacleDistanceGradient.
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 | ||
) | [inline, virtual] |
Called by STOMP at the end of each iteration.
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.
virtual bool stomp_moveit::cost_functions::StompCostFunction::setMotionPlanRequest | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const moveit_msgs::MotionPlanRequest & | req, | ||
const stomp_core::StompConfiguration & | config, | ||
moveit_msgs::MoveItErrorCodes & | error_code | ||
) | [pure virtual] |
Stores the planning details which will be used during the costs calculations.
planning_scene | A smart pointer to the planning scene |
req | The motion planning request |
config | The Stomp configuration. |
error_code | Moveit error code. |
Implemented in stomp_moveit::cost_functions::CollisionCheck, and stomp_moveit::cost_functions::ObstacleDistanceGradient.
double stomp_moveit::cost_functions::StompCostFunction::cost_weight_ [protected] |
Definition at line 164 of file stomp_cost_function.h.