Public Member Functions | Protected Attributes | List of all members
stomp_moveit::update_filters::TrajectoryVisualization Class Reference

Publishes rviz markers to visualize the optimized trajectory. More...

#include <trajectory_visualization.h>

Inheritance diagram for stomp_moveit::update_filters::TrajectoryVisualization:
Inheritance graph
[legend]

Public Member Functions

virtual bool configure (const XmlRpc::XmlRpcValue &config) override
 see base class for documentation
 
virtual void done (bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters) override
 Called by the Stomp at the end of the optimization process. More...
 
virtual bool filter (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd &parameters, Eigen::MatrixXd &updates, bool &filtered) override
 Publishes rviz markers to visualize the optimized trajectory at each iteration. More...
 
virtual std::string getGroupName () const override
 
virtual std::string getName () const override
 
virtual bool initialize (moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override
 see base class for documentation
 
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
 see base class for documentation
 
- Public Member Functions inherited from stomp_moveit::update_filters::StompUpdateFilter
virtual void postIteration (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, double cost, const Eigen::MatrixXd &parameters)
 Called by STOMP at the end of each iteration. More...
 

Protected Attributes

std_msgs::ColorRGBA error_rgb_
 
std::string group_name_
 
double line_width_
 
std::string marker_namespace_
 
std::string marker_topic_
 
std::string name_
 
ros::NodeHandle nh_
 
bool publish_intermediate_
 
std_msgs::ColorRGBA rgb_
 
moveit::core::RobotModelConstPtr robot_model_
 
moveit::core::RobotStatePtr state_
 
Eigen::MatrixXd tool_traj_line_
 
visualization_msgs::Marker tool_traj_marker_
 
ros::Publisher viz_pub_
 

Detailed Description

Publishes rviz markers to visualize the optimized trajectory.

Examples:
All examples are located here STOMP MoveIt! examples

Definition at line 49 of file trajectory_visualization.h.

Member Function Documentation

void stomp_moveit::update_filters::TrajectoryVisualization::done ( bool  success,
int  total_iterations,
double  final_cost,
const Eigen::MatrixXd &  parameters 
)
overridevirtual

Called by the 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 current iteration [num_dimensions x num_timesteps]

Reimplemented from stomp_moveit::update_filters::StompUpdateFilter.

Definition at line 243 of file trajectory_visualization.cpp.

bool stomp_moveit::update_filters::TrajectoryVisualization::filter ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
const Eigen::MatrixXd &  parameters,
Eigen::MatrixXd &  updates,
bool &  filtered 
)
overridevirtual

Publishes rviz markers to visualize the optimized trajectory at each iteration.

Parameters
start_timestepstart index into the 'parameters' array, usually 0.
num_timestepsnumber of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
parametersThe parameters generated in the previous iteration [num_dimensions x num_timesteps]
updatesThe updates to be applied to the parameters [num_dimensions x num_timesteps]
filteredAlways false as this filter never changes the updates values.
Returns
false if there was an irrecoverable failure, true otherwise.

Implements stomp_moveit::update_filters::StompUpdateFilter.

Definition at line 218 of file trajectory_visualization.cpp.


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


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Fri May 8 2020 03:35:47