post_processor.hpp
Go to the documentation of this file.
1 #ifndef FANUC_POST_PROCESSOR_HPP
2 #define FANUC_POST_PROCESSOR_HPP
3 
4 #include <algorithm>
8 #include <fstream>
9 #include <limits>
10 #include <ros/ros.h>
11 #include <stdexcept>
12 #include <string>
13 
14 namespace fanuc_post_processor
15 {
29 {
30 public:
32  {
34  };
35 
36  enum SpeedType
37  {
39  };
40 
42  {
44  };
45 
46 public:
49 
51 
61  typedef std::string ProgramName;
62  typedef std::string Program;
63  unsigned generatePrograms(std::vector<std::pair<ProgramName, Program>> &output_programs,
64  const unsigned lines_per_program = 0);
65 
66  void clearProgram();
67 
68  void useLineNumbers(bool line_numbers);
69 
78  void
79  uploadToFtp(const std::vector<std::pair<ProgramName, Program>> programs,
80  const std::string ip_address,
81  const std::string port_number = "21",
82  const std::string username = "",
83  const std::string password = "");
84 
91  void setProgramName(std::string name);
92 
99  void setProgramComment(const std::string comment);
100 
105  void setMemorySize(const unsigned size);
106 
112 
117  void setApplicative(const std::string appl);
118 
124  void
125  appendPose(FanucPose &pose);
126 
134  void
135  appendPoseId(FanucPose &pose);
136 
141  void
142  appendComment(const std::string comment);
143 
147  void
148  appendEmptyLine();
149 
155  void
156  appendDigitalOutput(const unsigned digital_out_id,
157  const bool state);
158 
165  void
166  appendDigitalOutput(const unsigned digital_out_id,
167  const double pulse_time);
168 
174  void
175  appendWait(const double time);
176 
182  void
183  appendWait(const unsigned digital_in_id,
184  bool state);
185 
190  void
191  appendUFrame(const unsigned uf_id);
192 
197  void
198  appendUTool(const unsigned ut_id);
199 
205  void
206  appendGroupOutput(const unsigned id,
207  const unsigned value);
208 
214  void
215  appendSetRegister(const unsigned r_id,
216  const double value);
217 
223  void
224  appendCall(const std::string program_name);
225 
231  void
232  appendRun(const std::string program_name);
233 
239  void
240  appendLabel(const unsigned id);
241 
247  void
248  appendJumpLabel(const unsigned id);
249 
254  void
255  appendDataMonitorStart(const unsigned id);
256 
260  void
262 
270  void appendFor(const unsigned reg_id,
271  const std::string start,
272  const std::string stop);
273 
281  void appendFor(const unsigned reg_id,
282  const unsigned start,
283  const unsigned stop);
284 
289  void appendEndFor();
290 
294  void appendCustomCommand(const std::string command);
295 
296  bool getPoseFromId(const unsigned pose_id,
297  FanucPose &pose);
298 
299 private:
300  void prependLineNumber(std::string &line,
301  const unsigned number);
302 
303  bool tweakProgramName(ProgramName &name,
304  const unsigned number);
305 
306  const unsigned program_name_max_size_ = 36;
307 
309  {
310  if (perm == READ_WRITE)
311  return "READ_WRITE";
312  if (perm == READ)
313  return "READ";
314  else
315  return "";
316  }
317 
318  std::string program_name_;
319 
320  std::string program_comment_;
321 
323 
324  std::string applicative_;
325 
326  std::vector<std::shared_ptr<FanucCommand>> commands_;
327 
328  std::vector<unsigned> labels_id_;
329 
331 
335  unsigned for_count_;
336 
341  std::vector<FanucPose> poses_;
342 };
343 
344 }
345 #endif
Definition: axis.hpp:6
std::string Program
void appendGroupOutput(const unsigned id, const unsigned value)
void appendCall(const std::string program_name)
bool line_numbers_
void appendComment(const std::string comment)
void setPermissions(const FanucPostProcessor::Permissions perms)
Definition: pose.hpp:12
FanucPostProcessor()
Default Constructor.
void setMemorySize(const unsigned size)
void appendCustomCommand(const std::string command)
std::string ProgramName
void appendSetRegister(const unsigned r_id, const double value)
void prependLineNumber(std::string &line, const unsigned number)
~FanucPostProcessor()
std::string program_name_
unsigned generatePrograms(std::vector< std::pair< ProgramName, Program >> &output_programs, const unsigned lines_per_program=0)
void appendPose(FanucPose &pose)
std::string program_comment_
void appendPoseId(FanucPose &pose)
void appendJumpLabel(const unsigned id)
void appendLabel(const unsigned id)
void appendDigitalOutput(const unsigned digital_out_id, const bool state)
FanucPostProcessor class.
bool tweakProgramName(ProgramName &name, const unsigned number)
void appendEndFor()
std::vector< unsigned > labels_id_
Permissions
void setProgramName(std::string name)
std::string applicative_
void appendEmptyLine()
void useLineNumbers(bool line_numbers)
const unsigned program_name_max_size_
SpeedType
std::vector< FanucPose > poses_
bool getPoseFromId(const unsigned pose_id, FanucPose &pose)
std::vector< std::shared_ptr< FanucCommand > > commands_
void appendDataMonitorStart(const unsigned id)
void setProgramComment(const std::string comment)
void setApplicative(const std::string appl)
void appendWait(const double time)
void appendUFrame(const unsigned uf_id)
unsigned for_count_
void clearProgram()
void uploadToFtp(const std::vector< std::pair< ProgramName, Program >> programs, const std::string ip_address, const std::string port_number="21", const std::string username="", const std::string password="")
void appendUTool(const unsigned ut_id)
std::string permissionsToString(Permissions perm)
MovementType
void appendFor(const unsigned reg_id, const std::string start, const std::string stop)
void appendRun(const std::string program_name)
FanucPostProcessor::Permissions permissions_
void appendDataMonitorStop()


fanuc_post_processor
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Jun 10 2019 13:16:56