This defines stomp's optimization task. More...
#include <memory>
#include <moveit_msgs/MotionPlanRequest.h>
#include <moveit/robot_model/robot_model.h>
#include <stomp_core/task.h>
#include <stomp_moveit/cost_functions/stomp_cost_function.h>
#include <XmlRpcValue.h>
#include <pluginlib/class_loader.h>
#include <stomp_moveit/noise_generators/stomp_noise_generator.h>
#include <stomp_moveit/noisy_filters/stomp_noisy_filter.h>
#include <stomp_moveit/update_filters/stomp_update_filter.h>
Go to the source code of this file.
Classes | |
class | stomp_moveit::StompOptimizationTask |
Loads and manages the STOMP plugins during the planning process. More... | |
Namespaces | |
namespace | stomp_moveit |
Typedefs | |
typedef std::shared_ptr < CostFunctionLoader > | stomp_moveit::CostFuctionLoaderPtr |
typedef pluginlib::ClassLoader < stomp_moveit::cost_functions::StompCostFunction > | stomp_moveit::CostFunctionLoader |
typedef pluginlib::ClassLoader < stomp_moveit::noise_generators::StompNoiseGenerator > | stomp_moveit::NoiseGeneratorLoader |
typedef std::shared_ptr < NoiseGeneratorLoader > | stomp_moveit::NoiseGeneratorLoaderPtr |
typedef pluginlib::ClassLoader < stomp_moveit::noisy_filters::StompNoisyFilter > | stomp_moveit::NoisyFilterLoader |
typedef std::shared_ptr < NoisyFilterLoader > | stomp_moveit::NoisyFilterLoaderPtr |
typedef pluginlib::ClassLoader < stomp_moveit::update_filters::StompUpdateFilter > | stomp_moveit::UpdateFilterLoader |
typedef std::shared_ptr < UpdateFilterLoader > | stomp_moveit::UpdateFilterLoaderPtr |
This defines stomp's optimization task.
Definition in file stomp_optimization_task.h.