moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
stomp_moveit::ComposableTask Class Referencefinal

#include <stomp_moveit_task.hpp>

Inheritance diagram for stomp_moveit::ComposableTask:
Inheritance graph
[legend]
Collaboration diagram for stomp_moveit::ComposableTask:
Collaboration graph
[legend]

Public Member Functions

 ComposableTask (NoiseGeneratorFn noise_generator_fn, CostFn cost_fn, FilterFn filter_fn, PostIterationFn post_iteration_fn, DoneFn done_fn)
 
 ~ComposableTask ()=default
 
bool generateNoisyParameters (const Eigen::MatrixXd &parameters, std::size_t, std::size_t, int, int, Eigen::MatrixXd &parameters_noise, Eigen::MatrixXd &noise) override
 Generates a noisy trajectory from the parameters. More...
 
bool computeCosts (const Eigen::MatrixXd &parameters, std::size_t, std::size_t, int, Eigen::VectorXd &costs, bool &validity) override
 computes the state costs as a function of the distance from the bias parameters More...
 
bool computeNoisyCosts (const Eigen::MatrixXd &parameters, std::size_t, std::size_t, int, int, Eigen::VectorXd &costs, bool &validity) override
 computes the state costs as a function of the distance from the bias parameters More...
 
bool filterParameterUpdates (std::size_t, std::size_t, int, const Eigen::MatrixXd &parameters, Eigen::MatrixXd &updates) override
 Filters the given parameters which is applied after the update. It could be used for clipping of joint limits or projecting into the null space of the Jacobian. More...
 
void postIteration (std::size_t, std::size_t, int iteration_number, double cost, const Eigen::MatrixXd &parameters) override
 Called by STOMP at the end of each iteration. More...
 
void done (bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters) override
 Called by Stomp at the end of the optimization process. More...
 

Detailed Description

Definition at line 78 of file stomp_moveit_task.hpp.

Constructor & Destructor Documentation

◆ ComposableTask()

stomp_moveit::ComposableTask::ComposableTask ( NoiseGeneratorFn  noise_generator_fn,
CostFn  cost_fn,
FilterFn  filter_fn,
PostIterationFn  post_iteration_fn,
DoneFn  done_fn 
)
inline

Definition at line 81 of file stomp_moveit_task.hpp.

◆ ~ComposableTask()

stomp_moveit::ComposableTask::~ComposableTask ( )
default

Member Function Documentation

◆ computeCosts()

bool stomp_moveit::ComposableTask::computeCosts ( const Eigen::MatrixXd &  parameters,
std::size_t  ,
std::size_t  ,
int  ,
Eigen::VectorXd &  costs,
bool &  validity 
)
inlineoverride

computes the state costs as a function of the distance from the bias parameters

Parameters
parametersA matrix [num_dimensions][num_parameters] of the policy parameters to execute
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
costsA vector containing the state costs per timestep.
validityWhether or not the trajectory is valid
Returns
True if cost were properly computed, otherwise false

Definition at line 121 of file stomp_moveit_task.hpp.

◆ computeNoisyCosts()

bool stomp_moveit::ComposableTask::computeNoisyCosts ( const Eigen::MatrixXd &  parameters,
std::size_t  ,
std::size_t  ,
int  ,
int  ,
Eigen::VectorXd &  costs,
bool &  validity 
)
inlineoverride

computes the state costs as a function of the distance from the bias parameters

Parameters
parametersA matrix [num_dimensions][num_parameters] of the policy parameters to execute
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
rollout_numberThe index of the noisy trajectory.
costsA vector containing the state costs per timestep.
validityWhether or not the trajectory is valid
Returns
True if cost were properly computed, otherwise false

Definition at line 138 of file stomp_moveit_task.hpp.

◆ done()

void stomp_moveit::ComposableTask::done ( bool  success,
int  total_iterations,
double  final_cost,
const Eigen::MatrixXd &  parameters 
)
inlineoverride

Called by Stomp at the end of the optimization process.

Parameters
successWhether the optimization succeeded
total_iterationsNumber of iterations used
final_costThe cost value after optimizing.
parametersThe parameters generated at the end of the optimization [num_dimensions x num_timesteps]

Definition at line 185 of file stomp_moveit_task.hpp.

◆ filterParameterUpdates()

bool stomp_moveit::ComposableTask::filterParameterUpdates ( std::size_t  ,
std::size_t  ,
int  ,
const Eigen::MatrixXd &  parameters,
Eigen::MatrixXd &  updates 
)
inlineoverride

Filters the given parameters which is applied after the update. It could be used for clipping of joint limits or projecting into the null space of the Jacobian.

Parameters
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
parametersThe optimized parameters
updatesThe updates to the parameters
Returns
True if successful, otherwise false

Definition at line 156 of file stomp_moveit_task.hpp.

◆ generateNoisyParameters()

bool stomp_moveit::ComposableTask::generateNoisyParameters ( const Eigen::MatrixXd &  parameters,
std::size_t  ,
std::size_t  ,
int  ,
int  ,
Eigen::MatrixXd &  parameters_noise,
Eigen::MatrixXd &  noise 
)
inlineoverride

Generates a noisy trajectory from the parameters.

Parameters
parametersA matrix [num_dimensions][num_parameters] of the current optimized parameters
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
rollout_numberThe index of the noisy trajectory.
parameters_noiseThe parameters + noise
noiseThe noise applied to the parameters
Returns
True if cost were properly computed, otherwise false

Definition at line 104 of file stomp_moveit_task.hpp.

◆ postIteration()

void stomp_moveit::ComposableTask::postIteration ( std::size_t  ,
std::size_t  ,
int  iteration_number,
double  cost,
const Eigen::MatrixXd &  parameters 
)
inlineoverride

Called by STOMP at the end of each iteration.

Parameters
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
costThe cost value for the current parameters.
parametersThe value of the parameters at the end of the current iteration [num_dimensions x num_timesteps].

Definition at line 171 of file stomp_moveit_task.hpp.


The documentation for this class was generated from the following file: