trajectory_visualization.h
Go to the documentation of this file.
1 
26 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_TRAJECTORY_VISUALIZATION_H_
27 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_TRAJECTORY_VISUALIZATION_H_
28 
29 #include <ros/node_handle.h>
30 #include <ros/publisher.h>
31 #include <Eigen/Core>
32 #include <geometry_msgs/Point.h>
34 #include <visualization_msgs/Marker.h>
35 
36 namespace stomp_moveit
37 {
38 namespace update_filters
39 {
40 
50 {
51 public:
53  virtual ~TrajectoryVisualization();
54 
56  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
57  const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
58 
60  virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
61 
63  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
64  const moveit_msgs::MotionPlanRequest &req,
65  const stomp_core::StompConfiguration &config,
66  moveit_msgs::MoveItErrorCodes& error_code) override;
67 
79  virtual bool filter(std::size_t start_timestep,
80  std::size_t num_timesteps,
81  int iteration_number,
82  const Eigen::MatrixXd& parameters,
83  Eigen::MatrixXd& updates,
84  bool& filtered) override;
85 
94  virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters) override;
95 
96 
97  virtual std::string getName() const override
98  {
99  return name_ + "/" + group_name_;
100  }
101 
102 
103  virtual std::string getGroupName() const override
104  {
105  return group_name_;
106  }
107 
108 
109 protected:
110 
111  // identity
112  std::string name_;
113 
114  // robot
115  std::string group_name_;
116  moveit::core::RobotModelConstPtr robot_model_;
117  moveit::core::RobotStatePtr state_;
118 
119  // ros comm
120  ros::NodeHandle nh_;
121  ros::Publisher viz_pub_;
122 
123  // parameters
124  double line_width_;
125  std_msgs::ColorRGBA rgb_;
126  std_msgs::ColorRGBA error_rgb_;
127  bool publish_intermediate_;
128  std::string marker_topic_;
129  std::string marker_namespace_;
130 
131  // tool trajectory
132  Eigen::MatrixXd tool_traj_line_;
133  visualization_msgs::Marker tool_traj_marker_;
134 
135 
136 };
137 
138 } /* namespace filters */
139 } /* namespace stomp_moveit */
140 
141 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_TRAJECTORY_VISUALIZATION_H_ */
Publishes rviz markers to visualize the optimized trajectory.
virtual bool configure(const XmlRpc::XmlRpcValue &config) override
see base class for documentation
Interface class which applies filtering methods to the update parameters before it is added onto the ...
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.
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 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.
This is the base class for all stomp update filters.
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


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