This class generates noisy trajectories to an under-constrained cartesian goal pose.
More...
#include <goal_guided_multivariate_gaussian.h>
|
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) |
| Called by the Stomp at the end of the optimization process. More...
|
|
virtual bool | generateNoise (const Eigen::MatrixXd ¶meters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd ¶meters_noise, Eigen::MatrixXd &noise) override |
| Generates a noisy trajectory from the parameters. More...
|
|
virtual std::string | getGroupName () const |
|
virtual std::string | getName () const |
|
| GoalGuidedMultivariateGaussian () |
|
virtual bool | initialize (moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override |
| Initializes and configures. 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. More...
|
|
virtual | ~GoalGuidedMultivariateGaussian () |
|
virtual void | postIteration (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, double cost, const Eigen::MatrixXd ¶meters) |
|
This class generates noisy trajectories to an under-constrained cartesian goal pose.
- Examples:
- All examples are located here STOMP Plugins Examples
Definition at line 51 of file goal_guided_multivariate_gaussian.h.
stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::GoalGuidedMultivariateGaussian |
( |
| ) |
|
stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::~GoalGuidedMultivariateGaussian |
( |
| ) |
|
|
virtual |
bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::configure |
( |
const XmlRpc::XmlRpcValue & |
config | ) |
|
|
overridevirtual |
virtual void stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::done |
( |
bool |
success, |
|
|
int |
total_iterations, |
|
|
double |
final_cost, |
|
|
const Eigen::MatrixXd & |
parameters |
|
) |
| |
|
inlinevirtual |
bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::generateNoise |
( |
const Eigen::MatrixXd & |
parameters, |
|
|
std::size_t |
start_timestep, |
|
|
std::size_t |
num_timesteps, |
|
|
int |
iteration_number, |
|
|
int |
rollout_number, |
|
|
Eigen::MatrixXd & |
parameters_noise, |
|
|
Eigen::MatrixXd & |
noise |
|
) |
| |
|
overridevirtual |
Generates a noisy trajectory from the parameters.
- Parameters
-
parameters | The current value of the optimized parameters [num_dimensions x num_parameters] |
start_timestep | 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 |
rollout_number | The index of the noisy trajectory. |
parameters_noise | The parameters + noise |
noise | The noise applied to the parameters |
- Returns
- true if cost were properly computed, false otherwise.
Implements stomp_moveit::noise_generators::StompNoiseGenerator.
Definition at line 247 of file goal_guided_multivariate_gaussian.cpp.
bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::generateRandomGoal |
( |
const Eigen::VectorXd & |
reference_joint_pose, |
|
|
Eigen::VectorXd & |
goal_joint_pose |
|
) |
| |
|
protectedvirtual |
Genereates a random tool pose by apply noise on the redundant axis to a reference tool pose;.
- Parameters
-
reference_joint_pose | Joint position used in computing the reference tool pose with FK |
goal_joint_pose | The joint position corresponding to the randomized tool pose |
- Returns
- True if succeded, false otherwise
Definition at line 292 of file goal_guided_multivariate_gaussian.cpp.
virtual std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::getGroupName |
( |
| ) |
const |
|
inlinevirtual |
virtual std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::getName |
( |
| ) |
const |
|
inlinevirtual |
bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::initialize |
( |
moveit::core::RobotModelConstPtr |
robot_model_ptr, |
|
|
const std::string & |
group_name, |
|
|
const XmlRpc::XmlRpcValue & |
config |
|
) |
| |
|
overridevirtual |
std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::group_ |
|
protected |
stomp_moveit::utils::kinematics::IKSolverPtr stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::ik_solver_ |
|
protected |
std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::name_ |
|
protected |
Eigen::VectorXd stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::raw_noise_ |
|
protected |
moveit::core::RobotModelConstPtr stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::robot_model_ |
|
protected |
moveit::core::RobotStatePtr stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::state_ |
|
protected |
std::vector<double> stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::stddev_ |
|
protected |
Eigen::VectorXd stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::tool_goal_tolerance_ |
|
protected |
std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::tool_link_ |
|
protected |
std::vector<utils::MultivariateGaussianPtr> stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::traj_noise_generators_ |
|
protected |
The documentation for this class was generated from the following files: