trajectory_visualization.h
Go to the documentation of this file.
00001 
00026 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_TRAJECTORY_VISUALIZATION_H_
00027 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_TRAJECTORY_VISUALIZATION_H_
00028 
00029 #include <ros/node_handle.h>
00030 #include <ros/publisher.h>
00031 #include <Eigen/Core>
00032 #include <geometry_msgs/Point.h>
00033 #include <stomp_moveit/update_filters/stomp_update_filter.h>
00034 #include <visualization_msgs/Marker.h>
00035 
00036 namespace stomp_moveit
00037 {
00038 namespace update_filters
00039 {
00040 
00049 class TrajectoryVisualization : public StompUpdateFilter
00050 {
00051 public:
00052   TrajectoryVisualization();
00053   virtual ~TrajectoryVisualization();
00054 
00056   virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00057                           const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
00058 
00060   virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
00061 
00063   virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00064                    const moveit_msgs::MotionPlanRequest &req,
00065                    const stomp_core::StompConfiguration &config,
00066                    moveit_msgs::MoveItErrorCodes& error_code) override;
00067 
00079   virtual bool filter(std::size_t start_timestep,
00080                       std::size_t num_timesteps,
00081                       int iteration_number,
00082                       const Eigen::MatrixXd& parameters,
00083                       Eigen::MatrixXd& updates,
00084                       bool& filtered) override;
00085 
00094   virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters) override;
00095 
00096 
00097   virtual std::string getName() const override
00098   {
00099     return name_ + "/" + group_name_;
00100   }
00101 
00102 
00103   virtual std::string getGroupName() const override
00104   {
00105     return group_name_;
00106   }
00107 
00108 
00109 protected:
00110 
00111   // identity
00112   std::string name_;
00113 
00114   // robot
00115   std::string group_name_;
00116   moveit::core::RobotModelConstPtr robot_model_;
00117   moveit::core::RobotStatePtr state_;
00118 
00119   // ros comm
00120   ros::NodeHandle nh_;
00121   ros::Publisher viz_pub_;
00122 
00123   // parameters
00124   double line_width_;
00125   std_msgs::ColorRGBA rgb_;
00126   std_msgs::ColorRGBA error_rgb_;
00127   bool publish_intermediate_;
00128   std::string marker_topic_;
00129   std::string marker_namespace_;
00130 
00131   // tool trajectory
00132   Eigen::MatrixXd tool_traj_line_;
00133   visualization_msgs::Marker tool_traj_marker_;
00134 
00135 
00136 };
00137 
00138 } /* namespace filters */
00139 } /* namespace stomp_moveit */
00140 
00141 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_TRAJECTORY_VISUALIZATION_H_ */


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