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 public:
39 
41 
51  using ProgramName = std::string;
52  using ProgramText = std::string;
53  using FanucProgram = std::pair<ProgramName, ProgramText>;
54  using FanucPrograms = std::vector<FanucProgram>;
55  unsigned generatePrograms(FanucPrograms &output_programs,
56  const unsigned lines_per_program = 0);
57 
58  void clearProgram();
59 
60  void useLineNumbers(bool line_numbers);
61 
70  void
71  uploadToFtp(const FanucPrograms programs,
72  const std::string ip_address,
73  const std::string port_number = "21",
74  const std::string username = "",
75  const std::string password = "");
76 
83  void setProgramName(ProgramName name);
84 
91  void setProgramComment(const std::string comment);
92 
97  void setMemorySize(const unsigned size);
98 
104 
109  void setApplicative(const std::string appl);
110 
116  void
117  appendPose(FanucPose &pose);
118 
126  void
127  appendPoseId(FanucPose &pose);
128 
133  void
134  appendComment(const std::string comment);
135 
139  void
140  appendEmptyLine();
141 
147  void
148  appendDigitalOutput(const unsigned digital_out_id,
149  const bool state);
150 
157  void
158  appendDigitalOutput(const unsigned digital_out_id,
159  const double pulse_time);
160 
166  void
167  appendWait(const double time);
168 
173  void
174  appendTrackDPM(const unsigned number);
175 
179  void
180  appendTrackEnd();
181 
187  void
188  appendWait(const unsigned digital_in_id,
189  const bool state);
190 
196  void
197  appendWait(const unsigned group_id,
198  const unsigned value);
199 
204  void
205  appendTimerReset(const unsigned id);
206 
211  void
212  appendTimerStart(const unsigned id);
213 
218  void
219  appendTimerStop(const unsigned id);
220 
225  void
226  appendUFrame(const unsigned uf_id);
227 
232  void
233  appendUTool(const unsigned ut_id);
234 
240  void
241  appendGroupOutput(const unsigned id,
242  const unsigned value);
243 
249  void
250  appendSetRegister(const unsigned r_id,
251  const double value);
252 
258  void
259  appendSetRegister(const unsigned r_id,
260  const unsigned value);
261 
268  void
269  appendSetRegisterToRegister(const unsigned r1_id,
270  const unsigned r2_id);
271 
277  void
278  appendSetFlag(const unsigned f_id,
279  const bool value);
280 
286  void
287  appendCall(const std::string program_name);
288 
294  void
295  appendRun(const std::string program_name);
296 
302  void
303  appendLabel(const unsigned id);
304 
310  void
311  appendJumpLabel(const unsigned id);
312 
317  void
318  appendDataMonitorStart(const unsigned id);
319 
323  void
325 
333  void appendFor(const unsigned reg_id,
334  const std::string start,
335  const std::string stop);
336 
344  void appendFor(const unsigned reg_id,
345  const unsigned start,
346  const unsigned stop);
347 
352  void appendEndFor();
353 
357  void appendEndProgram(const bool call_next_program);
358 
362  void appendCustomCommand(const std::string command);
363 
364  bool getPoseFromId(const unsigned pose_id,
365  FanucPose &pose);
366 
367 private:
368  void prependLineNumber(std::string &line,
369  const unsigned number);
370 
371  bool tweakProgramName(ProgramName &name,
372  const unsigned number);
373 
374  const unsigned program_name_max_size_ = 36;
375 
377  {
378  if (perm == READ_WRITE)
379  return "READ_WRITE";
380  if (perm == READ)
381  return "READ";
382  else
383  return "";
384  }
385 
387 
388  std::string program_comment_;
389 
391 
392  std::string applicative_;
393 
394  std::vector<std::shared_ptr<FanucCommand>> commands_;
395 
396  std::vector<unsigned> labels_id_;
397 
399 
403  unsigned for_count_;
404 
409  std::vector<FanucPose> poses_;
410 };
411 
412 }
413 #endif
void uploadToFtp(const FanucPrograms programs, const std::string ip_address, const std::string port_number="21", const std::string username="", const std::string password="")
Definition: axis.hpp:6
void appendGroupOutput(const unsigned id, const unsigned value)
void appendCall(const std::string program_name)
bool line_numbers_
void appendSetFlag(const unsigned f_id, const bool value)
void appendComment(const std::string comment)
void setPermissions(const FanucPostProcessor::Permissions perms)
Definition: pose.hpp:13
FanucPostProcessor()
Default Constructor.
void setMemorySize(const unsigned size)
void appendTimerStart(const unsigned id)
void appendCustomCommand(const std::string command)
std::pair< ProgramName, ProgramText > FanucProgram
void appendSetRegister(const unsigned r_id, const double value)
void prependLineNumber(std::string &line, const unsigned number)
~FanucPostProcessor()
void appendPose(FanucPose &pose)
std::string program_comment_
void appendPoseId(FanucPose &pose)
void appendJumpLabel(const unsigned id)
void appendLabel(const unsigned id)
void setProgramName(ProgramName name)
std::string ProgramText
void appendDigitalOutput(const unsigned digital_out_id, const bool state)
FanucPostProcessor class.
bool tweakProgramName(ProgramName &name, const unsigned number)
unsigned generatePrograms(FanucPrograms &output_programs, const unsigned lines_per_program=0)
void appendEndFor()
std::vector< unsigned > labels_id_
Permissions
void appendTimerReset(const unsigned id)
ProgramName program_name_
std::string applicative_
std::string ProgramName
void appendEmptyLine()
void appendEndProgram(const bool call_next_program)
void useLineNumbers(bool line_numbers)
const unsigned program_name_max_size_
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)
std::vector< FanucProgram > FanucPrograms
void appendWait(const double time)
void appendUFrame(const unsigned uf_id)
void appendSetRegisterToRegister(const unsigned r1_id, const unsigned r2_id)
unsigned for_count_
void clearProgram()
void appendUTool(const unsigned ut_id)
std::string permissionsToString(Permissions perm)
void appendFor(const unsigned reg_id, const std::string start, const std::string stop)
void appendRun(const std::string program_name)
void appendTrackEnd()
FanucPostProcessor::Permissions permissions_
void appendDataMonitorStop()
void appendTimerStop(const unsigned id)
void appendTrackDPM(const unsigned number)


fanuc_post_processor
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Feb 28 2022 22:20:38