1 #ifndef RAM_PATH_PLANNING_POST_PROCESSOR_HPP 2 #define RAM_PATH_PLANNING_POST_PROCESSOR_HPP 6 #include <Eigen/Geometry> 9 #include <ram_msgs/AdditiveManufacturingTrajectory.h> 10 #include <ram_utils/GetStartPose.h> 11 #include <ram_utils/GetTool.h> 12 #include <ram_utils/GetTrajectoryInfos.h> 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");
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);
96 std::vector<std::pair<std::string, std::string>> &programs);
99 saveToFiles(
const std::string directory,
const std::string file_extension =
"");
101 const ram_msgs::AdditiveManufacturingTrajectory&
traj()
125 std::vector<std::pair<std::string, std::string>>
programs_;
136 Eigen::Isometry3d
tool_ = Eigen::Isometry3d::Identity();
139 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual void changeLaserPowerBefore()
virtual void startFeedRateAfter()
std::string program_name_
void generatePrograms(const ram_msgs::AdditiveManufacturingTrajectory &trajectory, std::vector< std::pair< std::string, std::string >> &programs)
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 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
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()