Public Member Functions | Protected Attributes
stomp_moveit::noisy_filters::MultiTrajectoryVisualization Class Reference

Publishes rviz markers to visualize the noisy trajectories. More...

#include <multi_trajectory_visualization.h>

Inheritance diagram for stomp_moveit::noisy_filters::MultiTrajectoryVisualization:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool configure (const XmlRpc::XmlRpcValue &config) override
 see base class for documentation
virtual bool filter (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd &parameters, bool &filtered) override
 Creates rviz markers for visualizing the noisy trajectories, it does not change the parameters.
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
 MultiTrajectoryVisualization ()
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
virtual ~MultiTrajectoryVisualization ()

Protected Attributes

std::string group_name_
double line_width_
std::string marker_namespace_
std::string marker_topic_
std::string name_
ros::NodeHandle nh_
std_msgs::ColorRGBA rgb_
moveit::core::RobotModelConstPtr robot_model_
moveit::core::RobotStatePtr state_
visualization_msgs::MarkerArray tool_points_markers_
Eigen::MatrixXd tool_traj_line_
visualization_msgs::MarkerArray tool_traj_markers_
std::size_t traj_total_
ros::Publisher viz_pub_

Detailed Description

Publishes rviz markers to visualize the noisy trajectories.

Examples:
All examples are located here stomp_core examples

Definition at line 49 of file multi_trajectory_visualization.h.


Constructor & Destructor Documentation

Definition at line 94 of file multi_trajectory_visualization.cpp.

Definition at line 103 of file multi_trajectory_visualization.cpp.


Member Function Documentation

see base class for documentation

Implements stomp_moveit::noisy_filters::StompNoisyFilter.

Definition at line 126 of file multi_trajectory_visualization.cpp.

bool stomp_moveit::noisy_filters::MultiTrajectoryVisualization::filter ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
int  rollout_number,
Eigen::MatrixXd &  parameters,
bool &  filtered 
) [override, virtual]

Creates rviz markers for visualizing the noisy trajectories, it does not change the parameters.

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.
rollout_numberIndex of the noisy trajectory whose cost is being evaluated.
parametersOutput argument containing the parameters to be filtered [num_dimensions x num_timesteps].
filteredOutput argument that's set to 'true' if the parameters were changed according to the filtering method.
Returns:
false if there was an irrecoverable failure, true otherwise.

Implements stomp_moveit::noisy_filters::StompNoisyFilter.

Definition at line 214 of file multi_trajectory_visualization.cpp.

virtual std::string stomp_moveit::noisy_filters::MultiTrajectoryVisualization::getGroupName ( ) const [inline, override, virtual]
virtual std::string stomp_moveit::noisy_filters::MultiTrajectoryVisualization::getName ( ) const [inline, override, virtual]
bool stomp_moveit::noisy_filters::MultiTrajectoryVisualization::initialize ( moveit::core::RobotModelConstPtr  robot_model_ptr,
const std::string &  group_name,
const XmlRpc::XmlRpcValue config 
) [override, virtual]

see base class for documentation

Implements stomp_moveit::noisy_filters::StompNoisyFilter.

Definition at line 109 of file multi_trajectory_visualization.cpp.

bool stomp_moveit::noisy_filters::MultiTrajectoryVisualization::setMotionPlanRequest ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const moveit_msgs::MotionPlanRequest req,
const stomp_core::StompConfiguration &  config,
moveit_msgs::MoveItErrorCodes &  error_code 
) [override, virtual]

see base class for documentation

Implements stomp_moveit::noisy_filters::StompNoisyFilter.

Definition at line 168 of file multi_trajectory_visualization.cpp.


Member Data Documentation

Definition at line 103 of file multi_trajectory_visualization.h.

Definition at line 112 of file multi_trajectory_visualization.h.

Definition at line 115 of file multi_trajectory_visualization.h.

Definition at line 114 of file multi_trajectory_visualization.h.

Definition at line 100 of file multi_trajectory_visualization.h.

Definition at line 108 of file multi_trajectory_visualization.h.

Definition at line 113 of file multi_trajectory_visualization.h.

Definition at line 104 of file multi_trajectory_visualization.h.

Definition at line 105 of file multi_trajectory_visualization.h.

Definition at line 121 of file multi_trajectory_visualization.h.

Definition at line 119 of file multi_trajectory_visualization.h.

Definition at line 120 of file multi_trajectory_visualization.h.

Definition at line 118 of file multi_trajectory_visualization.h.

Definition at line 109 of file multi_trajectory_visualization.h.


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


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01