post_processor.hpp
Go to the documentation of this file.
1 #ifndef RAM_PATH_PLANNING_POST_PROCESSOR_HPP
2 #define RAM_PATH_PLANNING_POST_PROCESSOR_HPP
3 
4 #include <fstream>
5 #include <Eigen/Core>
6 #include <Eigen/Geometry>
7 
9 #include <ram_msgs/AdditiveManufacturingTrajectory.h>
10 #include <ram_utils/GetStartPose.h>
11 #include <ram_utils/GetTool.h>
12 #include <ram_utils/GetTrajectoryInfos.h>
13 #include <ros/ros.h>
14 
16 {
18 {
19 public:
20  PostProcessor(const std::string name = "Generic",
21  const std::string description = "A human readable textual output.\n"
22  "Not meant to be used by any kind of hardware.",
23  const std::string service_name = "ram/post_processors/generic");
24 
25  virtual ~PostProcessor()
26  {
27  }
28 
29  virtual void
30  addComment(const std::string comment);
31 
32  virtual void
33  addPose(const bool laser_power_start,
34  const bool laser_power_stop,
35  const bool laser_power_change,
36  const bool feed_rate_start,
37  const bool feed_rate_stop,
38  const bool feed_rate_change);
39 
40  virtual void
41  clearProgram();
42 
43  virtual void
45 
46  virtual void
48 
50  virtual void
52 
53  virtual void
55 
56  virtual void
58 
59  virtual void
61 
63  virtual void
65 
67  virtual void
69  virtual void
71  virtual void
73  virtual void
75  virtual void
77  virtual void
79 
81  virtual void
83  virtual void
85  virtual void
87  virtual void
89  virtual void
91  virtual void
93 
94  void
95  generatePrograms(const ram_msgs::AdditiveManufacturingTrajectory &trajectory,
96  std::vector<std::pair<std::string, std::string>> &programs);
97 
98  virtual void
99  saveToFiles(const std::string directory, const std::string file_extension = "");
100 
101  const ram_msgs::AdditiveManufacturingTrajectory& traj()
102  {
103  return trajectory_;
104  }
105 
106  typedef ram_msgs::AdditiveManufacturingTrajectory::_poses_type::const_iterator ram_pose_const_iterator;
107 
108  const ram_pose_const_iterator& currentPose()
109  {
110  return current_pose_;
111  }
112 
113  const std::string name_;
114  const std::string description_;
115  const std::string service_name_;
116 
117  std::string program_name_ = "program";
118  std::string program_comment_ = "comment";
119  bool verbose_comments_ = false;
120 
121 protected:
123  // Post-processor might generate multiple programs at once
124  // Pair: <program name, program content>
125  std::vector<std::pair<std::string, std::string>> programs_;
126 
127 private:
128  ram_msgs::AdditiveManufacturingTrajectory trajectory_;
129  ram_pose_const_iterator current_pose_ = trajectory_.poses.begin();
130 
134 
135  Eigen::Isometry3d start_pose_ = Eigen::Isometry3d::Identity();
136  Eigen::Isometry3d tool_ = Eigen::Isometry3d::Identity();
137 
138 public:
139  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
140  };
141 
142 }
143 #endif
virtual void changeLaserPowerBefore()
virtual void startFeedRateAfter()
std::string program_name_
ros::NodeHandle nh_
void generatePrograms(const ram_msgs::AdditiveManufacturingTrajectory &trajectory, std::vector< std::pair< std::string, std::string >> &programs)
const std::string name_
const ram_msgs::AdditiveManufacturingTrajectory & traj()
const ram_pose_const_iterator & currentPose()
virtual void clearProgram()
ram_msgs::AdditiveManufacturingTrajectory trajectory
Eigen::Isometry3d start_pose_
virtual void startPolygonBefore()
Polygons.
std::string program_comment_
virtual ~PostProcessor()
Eigen::Isometry3d tool_
virtual void startFeedRateBefore()
Feed rate.
ros::ServiceClient get_start_pose_client_
virtual void stopFeedRateBefore()
virtual void changeFeedRateBefore()
virtual void addComment(const std::string comment)
virtual void beforeGenerating()
const std::string description_
ros::ServiceClient get_trajectory_infos_client_
ros::ServiceClient get_tool_client_
virtual void startPolygonAfter()
virtual void stopLaserPowerAfter()
virtual void finishPolygonAfter()
virtual void saveToFiles(const std::string directory, const std::string file_extension="")
virtual void addPose(const bool laser_power_start, const bool laser_power_stop, const bool laser_power_change, const bool feed_rate_start, const bool feed_rate_stop, const bool feed_rate_change)
virtual void stopLaserPowerBefore()
std::vector< std::pair< std::string, std::string > > programs_
virtual void layerIndexChanged()
Layer change.
virtual void finishPolygonBefore()
PostProcessor(const std::string name="Generic", const std::string description="A human readable textual output.\n""Not meant to be used by any kind of hardware.", const std::string service_name="ram/post_processors/generic")
ram_msgs::AdditiveManufacturingTrajectory trajectory_
ram_msgs::AdditiveManufacturingTrajectory::_poses_type::const_iterator ram_pose_const_iterator
bool verbose_comments_
ram_pose_const_iterator current_pose_
virtual void changeFeedRateAfter()
virtual void changeLaserPowerAfter()
virtual void startLaserPowerBefore()
Laser power.
virtual void afterGenerating()
virtual void startLaserPowerAfter()
const std::string service_name_
virtual void stopFeedRateAfter()


ram_post_processor
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Jun 10 2019 14:50:06