post_processor.cpp
Go to the documentation of this file.
2 
3 namespace fanuc_post_processor
4 {
5 
7  program_name_("ros"),
8  program_comment_(""),
9  permissions_(READ_WRITE),
10  applicative_(""),
11  line_numbers_(true),
12  for_count_(0)
13 {
14 }
15 
17 {
18 }
19 
21  const unsigned lines_per_program)
22 {
23  output_programs.clear();
24 
25  if (lines_per_program == 1)
26  throw std::runtime_error("Need at least 2 instructions per program");
27 
28  const unsigned number_of_programs(
29  lines_per_program == 0 ? 1 : std::ceil((double)commands_.size() / lines_per_program));
30 
31  if (number_of_programs > 999)
32  throw std::runtime_error("More than 999 programs would be generated: " + std::to_string(number_of_programs));
33 
34  ProgramText program;
35  unsigned program_id(0);
36  unsigned line_count(0);
37 
38  std::map<unsigned, FanucPose> poses_in_program; // key is the original pose ID, FanucPose contains the 'new' pose ID
39  ProgramName program_name;
40  for (unsigned cmd_id(0); cmd_id < commands_.size(); ++cmd_id)
41  {
42  // Initialize program
43  if (program.empty())
44  {
45  // PROG
46  program.append("/PROG ");
47  program_name = program_name_;
48  if (!tweakProgramName(program_name, program_id))
49  return 0;
50  program.append(program_name);
51  program.append("\n");
52 
53  // ATTR
54  program.append("/ATTR");
55  program.append("\n");
56  program.append("COMMENT = \"" + program_comment_ + "\";");
57  program.append("\n");
58  program.append("PROTECT = " + permissionsToString(permissions_) + ";");
59  program.append("\n");
60 
61  // Default group
62  if (!poses_.empty() && poses_.front().groups_.size() > 4)
63  throw std::runtime_error("Poses have more than 4 groups");
64 
65  std::string default_group("1,*,*,*,*");
66 
67  if (!poses_.empty())
68  {
69  default_group = "";
70  const unsigned number_of_groups(poses_.front().groups_.size());
71 
72  // Add group
73  for (unsigned i(0); i < number_of_groups; ++i)
74  {
75  if (default_group.size() == 8) // Last group case
76  default_group.append("1");
77  else
78  default_group.append("1,");
79  }
80 
81  // Add empty
82  for (unsigned i(0); i < 5 - number_of_groups; ++i)
83  {
84  if (default_group.size() == 8) // Last group case
85  default_group.append("*");
86  else
87  default_group.append("*,");
88  }
89  }
90 
91  program.append("DEFAULT_GROUP = " + default_group + ";");
92  program.append("\n");
93 
94  // APPL
95  if (!applicative_.empty())
96  {
97  program.append("/APPL\n");
98  program.append(" " + applicative_ + ";");
99  program.append("\n");
100  }
101 
102  // MN
103  program.append("/MN");
104  program.append("\n");
105  }
106 
107  if (std::shared_ptr<FanucPoseCommand> pose_cmd = std::dynamic_pointer_cast<FanucPoseCommand>(commands_.at(cmd_id)))
108  {
109  // Check if pose is in the map
110  if (poses_in_program.find(pose_cmd->pose_.pose_id_) == poses_in_program.end())
111  {
112  // Pose is not in the map, we assign it a new ID and add it to the map
113  FanucPose modified_pose(pose_cmd->pose_);
114  modified_pose.pose_id_ = poses_in_program.size() + 1; // Pose ID starts at 1 (not zero)
115  poses_in_program.insert(std::pair<unsigned, FanucPose>(pose_cmd->pose_.pose_id_, modified_pose));
116  }
117  // If pose is in the map we don't need to do anything
118 
119  std::string line(poses_in_program.find(pose_cmd->pose_.pose_id_)->second.getMainLineString());
120  prependLineNumber(line, line_count++);
121  program.append(line);
122  }
123  else if (std::shared_ptr<FanucEndProgram> end_cmd = std::dynamic_pointer_cast<FanucEndProgram>(commands_.at(cmd_id)))
124  {
125  if (end_cmd->call_next_)
126  {
127  ProgramName next_program_name(program_name_);
128  if (!tweakProgramName(next_program_name, program_id + 1))
129  return 0;
130 
131  std::string call_line("CALL " + next_program_name + " ;\n");
132  prependLineNumber(call_line, line_count++);
133  program.append(call_line);
134  }
135 
136  // POS
137  program.append("/POS");
138  program.append("\n");
139 
140  for (auto pose_map : poses_in_program)
141  program.append(pose_map.second.getPoseLinesString());
142 
143  // END
144  program.append("/END\n\n");
145 
146  output_programs.push_back(FanucProgram(program_name, program));
147  ++program_id;
148  line_count = 0;
149  program.clear();
150  poses_in_program.clear();
151  continue;
152  }
153  else if (std::shared_ptr<FanucStringCommand> str_cmd = std::dynamic_pointer_cast<FanucStringCommand>(
154  commands_.at(cmd_id)))
155  {
156  std::string line(str_cmd->cmd_);
157  prependLineNumber(line, line_count++);
158  program.append(line);
159  }
160  else
161  throw std::runtime_error("Un-recognized FanucCommand!");
162 
163  program.append("\n");
164 
165  // Program limit hit
166  if (lines_per_program != 0 && line_count == lines_per_program - 1)
167  {
168  // Don't add a CALL if this is also the last command of the program
169  if (cmd_id == commands_.size() - 1)
170  break;
171 
172  ProgramName next_program_name(program_name_);
173  if (!tweakProgramName(next_program_name, program_id + 1))
174  return 0;
175 
176  std::string call_line("CALL " + next_program_name + " ;\n");
177  prependLineNumber(call_line, line_count++);
178  program.append(call_line);
179 
180  // POS
181  program.append("/POS");
182  program.append("\n");
183 
184  for (auto pose_map : poses_in_program)
185  program.append(pose_map.second.getPoseLinesString());
186 
187  // END
188  program.append("/END\n\n");
189 
190  output_programs.push_back(FanucProgram(program_name, program));
191  ++program_id;
192  line_count = 0;
193  program.clear();
194  poses_in_program.clear();
195  continue;
196  }
197  }
198 
199  if (program.empty())
200  return output_programs.size();
201 
202  // End of commands, finish last program generated
203  // POS
204  program.append("/POS");
205  program.append("\n");
206 
207  for (auto pose_map : poses_in_program)
208  program.append(pose_map.second.getPoseLinesString());
209 
210  // END
211  program.append("/END\n\n");
212  output_programs.push_back(FanucProgram(program_name, program));
213  return output_programs.size();
214 }
215 
217 {
218  commands_.clear();
219  poses_.clear();
220  labels_id_.clear();
221 }
222 
223 void FanucPostProcessor::useLineNumbers(bool line_numbers)
224 {
225  line_numbers_ = line_numbers;
226 }
227 
229  const std::string ip_address,
230  const std::string port_number,
231  const std::string username,
232  const std::string password)
233 {
234  // Write programs on disk
235  for (auto &program : programs)
236  {
237  std::ofstream ls_program;
238  ls_program.open("/tmp/" + program.first + ".ls");
239  if (!ls_program.is_open())
240  throw std::runtime_error("Could not open /tmp/" + program.first + ".ls for writing");
241 
242  ls_program << program.second;
243  ls_program.close();
244 
245  // Upload to the robot
246  ROS_INFO_STREAM("Trying to upload " + program.first + ".ls at " + ip_address);
247  try
248  {
250  curlite.set(CURLOPT_URL, "ftp://@" + ip_address + ":" + port_number + "/\\" + program.first + ".ls");
251  curlite.set(CURLOPT_USERNAME, username);
252  curlite.set(CURLOPT_PASSWORD, password);
253  curlite.set(CURLOPT_UPLOAD, true);
254 
255  // Open input file stream
256  std::ifstream ifs("/tmp/" + program.first + ".ls", std::ios::binary);
257  ifs >> curlite;
258 
259  double total_secs = curlite.getInfo<double>(CURLINFO_TOTAL_TIME);
260  ROS_INFO_STREAM("Upload time: " << total_secs << " s");
261  }
262  catch (std::exception &e)
263  {
264  throw std::runtime_error(e.what());
265  }
266  }
267 }
268 
270 {
271  if (name.empty())
272  throw std::runtime_error("Program name cannot be empty");
273  if (name.find(' ') != std::string::npos)
274  throw std::runtime_error("Program name cannot contain a space");
275  if (name.size() > program_name_max_size_)
276  name.resize(program_name_max_size_);
277 
278  program_name_ = name;
279  std::transform(program_name_.begin(), program_name_.end(), program_name_.begin(), ::toupper);
280 }
281 
282 void FanucPostProcessor::setProgramComment(const std::string comment)
283 {
284  program_comment_ = comment;
285 }
286 
288 {
289  permissions_ = perms;
290 }
291 
292 void FanucPostProcessor::setApplicative(const std::string appl)
293 {
294  applicative_ = appl;
295 }
296 
298 {
299  if (!pose.isValid())
300  throw std::runtime_error("Pose is not valid");
301 
302  if (!poses_.empty() && !pose.hasSameGroupsAxes(poses_.front()))
303  throw std::runtime_error("Pose does not have the same groups/axes of the first pose in the program");
304 
305  if (poses_.empty())
306  pose.pose_id_ = 1;
307  else
308  pose.pose_id_ = poses_.back().pose_id_ + 1;
309 
310  poses_.push_back(pose);
311  std::shared_ptr<FanucPoseCommand> cmd = std::make_shared<FanucPoseCommand>(pose);
312  commands_.push_back(cmd);
313 }
314 
315 void
317 {
318  if (pose.pose_id_ == 0)
319  throw std::runtime_error("Invalid pose id (0)");
320 
321  for (auto pose_tmp : poses_)
322  {
323  if (pose_tmp.pose_id_ == pose.pose_id_)
324  {
325  pose.groups_.clear(); // Remove these fields to avoid confusion
326  std::shared_ptr<FanucPoseCommand> cmd = std::make_shared<FanucPoseCommand>(pose);
327  cmd->pose_.groups_ = pose_tmp.groups_; // Copy robot pose
328 
329  if (!cmd->pose_.isValid())
330  throw std::runtime_error("Pose is not valid");
331 
332  commands_.push_back(cmd);
333  return;
334  }
335  }
336 
337  throw std::runtime_error("Pose ID " + std::to_string(pose.pose_id_) + " was not found");
338 }
339 
340 void FanucPostProcessor::appendComment(const std::string comment)
341 {
342  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("!" + comment + ";");
343  commands_.push_back(cmd);
344 }
345 
347 {
348  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(";");
349  commands_.push_back(cmd);
350 }
351 
352 void FanucPostProcessor::appendDigitalOutput(const unsigned digital_out_id,
353  const bool state)
354 {
355  const std::string DO_id(std::to_string(digital_out_id));
356  const std::string on_off(state == true ? "ON" : "OFF");
357  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("DO[" + DO_id + "]=" + on_off + ";");
358  commands_.push_back(cmd);
359 }
360 
361 void FanucPostProcessor::appendDigitalOutput(const unsigned digital_out_id,
362  const double pulse_time)
363 {
364  if (pulse_time <= 0)
365  throw std::runtime_error("Pulse time must be > 0");
366 
367  const std::string digital_output_id(std::to_string(digital_out_id));
368  std::ostringstream ss;
369  ss.imbue(std::locale("C")); // To ensure dot as a decimal separator
370  ss << std::fixed << std::setprecision(2);
371  ss << pulse_time;
372  const std::string time = ss.str();
373  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
374  "DO[" + digital_output_id + "]=PULSE," + time + "sec;");
375  commands_.push_back(cmd);
376 }
377 
378 void FanucPostProcessor::appendWait(const double time)
379 {
380  if (time <= 0)
381  throw std::runtime_error("Time must be >= 0");
382 
383  std::ostringstream ss;
384  ss.imbue(std::locale("C")); // To ensure dot as a decimal separator
385  ss << std::fixed << std::setprecision(2);
386  ss << time;
387  const std::string duration = ss.str();
388  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("WAIT " + duration + "(sec);");
389  commands_.push_back(cmd);
390 }
391 
392 void FanucPostProcessor::appendTrackDPM(const unsigned number)
393 {
394  if (number == 0)
395  throw std::runtime_error("Number must be >= 0");
396  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("Track DPM[" + std::to_string(number) + "];");
397  commands_.push_back(cmd);
398 }
399 
401 {
402  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("Track End;");
403  commands_.push_back(cmd);
404 }
405 
406 void FanucPostProcessor::appendWait(const unsigned digital_in_id,
407  const bool state)
408 {
409  const std::string DI_id(std::to_string(digital_in_id));
410  const std::string DI_state(state ? "ON" : "OFF");
411  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
412  "WAIT DI[" + DI_id + "]=" + DI_state + ";");
413  commands_.push_back(cmd);
414 }
415 
416 void FanucPostProcessor::appendWait(const unsigned go_id,
417  const unsigned value)
418 {
419  const std::string GO_id(std::to_string(go_id));
420  const std::string GO_value(std::to_string(value));
421  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
422  "WAIT GO[" + GO_id + "]=" + GO_value + ";");
423  commands_.push_back(cmd);
424 }
425 
427 {
428  if (id < 1)
429  throw std::runtime_error("Timer ID must be > 0");
430 
431  const std::string timer_id(std::to_string(id));
432  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
433  "TIMER[" + timer_id + "]=RESET;");
434  commands_.push_back(cmd);
435 }
436 
438 {
439  if (id < 1)
440  throw std::runtime_error("Timer ID must be > 0");
441 
442  const std::string timer_id(std::to_string(id));
443  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
444  "TIMER[" + timer_id + "]=START;");
445  commands_.push_back(cmd);
446 }
447 
448 void FanucPostProcessor::appendTimerStop(const unsigned id)
449 {
450  if (id < 1)
451  throw std::runtime_error("Timer ID must be > 0");
452 
453  const std::string timer_id(std::to_string(id));
454  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
455  "TIMER[" + timer_id + "]=STOP;");
456  commands_.push_back(cmd);
457 }
458 
459 void FanucPostProcessor::appendUFrame(const unsigned uf_id)
460 {
461  if (uf_id > 9)
462  throw std::runtime_error("UFrame number exceeds maximum of 9, UFrame ID given = " + std::to_string(uf_id));
463 
464  const std::string uframe(std::to_string(uf_id));
465  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("UFRAME_NUM=" + uframe + ";");
466  commands_.push_back(cmd);
467 }
468 
469 void FanucPostProcessor::appendUTool(const unsigned ut_id)
470 {
471  if (ut_id == 0 || ut_id > 9)
472  throw std::runtime_error("UTool ID must be between 1 and 9. UTool ID given = " + std::to_string(ut_id));
473 
474  const std::string utool(std::to_string(ut_id));
475  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("UTOOL_NUM=" + utool + ";");
476  commands_.push_back(cmd);
477 }
478 
480  const unsigned value)
481 {
482  const std::string group_id(std::to_string(id));
483  const std::string group_value(std::to_string(value));
484  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
485  "GO[" + group_id + "]=" + group_value + ";");
486  commands_.push_back(cmd);
487 }
488 
489 void FanucPostProcessor::appendSetRegister(const unsigned r_id,
490  const double value)
491 {
492  if (r_id == 0)
493  throw std::runtime_error("Register ID starts at 1. Given register ID = 0");
494 
495  const std::string id(std::to_string(r_id));
496  std::ostringstream ss;
497  ss.imbue(std::locale("C")); // To ensure dot as a decimal separator
498  ss << std::fixed << std::setprecision(2);
499  ss << value;
500  const std::string r_value = ss.str();
501  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("R[" + id + "]=" + r_value + ";");
502  commands_.push_back(cmd);
503 }
504 
505 void FanucPostProcessor::appendSetRegister(const unsigned r_id,
506  const unsigned value)
507 {
508  if (r_id == 0)
509  throw std::runtime_error("Register ID starts at 1. Given register ID = 0");
510 
511  const std::string id(std::to_string(r_id));
512  std::ostringstream ss;
513  ss << value;
514  const std::string r_value = ss.str();
515  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("R[" + id + "]=" + r_value + ";");
516  commands_.push_back(cmd);
517 }
518 
520  const unsigned r2_id)
521 {
522  if (r1_id == 0)
523  throw std::runtime_error("Register ID starts at 1. Given register 1 ID = 0");
524  if (r2_id == 0)
525  throw std::runtime_error("Register ID starts at 1. Given register 2 ID = 0");
526 
527  const std::string id1(std::to_string(r1_id));
528  const std::string id2(std::to_string(r2_id));
529  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("R[" + id1 + "]= R[" + id2 + "];");
530  commands_.push_back(cmd);
531 }
532 
533 void FanucPostProcessor::appendSetFlag(const unsigned f_id,
534  const bool value)
535 {
536  if (f_id == 0)
537  throw std::runtime_error("Flags ID starts at 1. Given register ID = 0");
538 
539  const std::string id(std::to_string(f_id));
540  const std::string f_value (value ? "ON" : "OFF");
541  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("F[" + id + "]=(" + f_value + ");");
542  commands_.push_back(cmd);
543 }
544 
545 void FanucPostProcessor::appendCall(const std::string program_name)
546 {
547  std::string name(program_name);
548  std::transform(name.begin(), name.end(), name.begin(), ::toupper);
549  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("CALL " + name + ";");
550  commands_.push_back(cmd);
551 }
552 
553 void FanucPostProcessor::appendRun(const std::string program_name)
554 {
555  std::string name(program_name);
556  std::transform(name.begin(), name.end(), name.begin(), ::toupper);
557  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("RUN " + name + ";");
558  commands_.push_back(cmd);
559 }
560 
561 void FanucPostProcessor::appendLabel(const unsigned id)
562 {
563  // Search if label is used, if not return false
564  for (std::vector<unsigned>::iterator iter(labels_id_.begin()); iter != labels_id_.end(); ++iter)
565  if (*iter == id)
566  throw std::runtime_error("Label ID does not exist. Given label ID = " + std::to_string(id));
567  labels_id_.push_back(id); // Label "id" is now available in appendJumpLabel
568 
569  const std::string lbl_id(std::to_string(id));
570  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("LBL[" + lbl_id + "];");
571  commands_.push_back(cmd);
572 }
573 
574 void FanucPostProcessor::appendJumpLabel(const unsigned id)
575 {
576  // Do not check if label is available, it might be declared after the JUMP
577  const std::string lbl_id(std::to_string(id));
578  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("JMP LBL[" + lbl_id + "];");
579  commands_.push_back(cmd);
580 }
581 
583 {
584  const std::string datamon_id(std::to_string(id));
585  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("Sample Start[" + datamon_id + "];");
586  commands_.push_back(cmd);
587 }
588 
590 {
591  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("Sample End;");
592  commands_.push_back(cmd);
593 }
594 
595 void FanucPostProcessor::appendFor(const unsigned reg_id,
596  const std::string start,
597  const std::string stop)
598 {
599  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
600  "FOR R[" + std::to_string(reg_id) + "]=" + start + " TO " + stop + ";");
601  commands_.push_back(cmd);
602  ++for_count_;
603 }
604 
605 void FanucPostProcessor::appendFor(const unsigned reg_id,
606  const unsigned start,
607  const unsigned stop)
608 {
609  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(
610  "FOR R[" + std::to_string(reg_id) + "]=" + std::to_string(start)
611  + " TO " + std::to_string(stop) + ";");
612  ++for_count_;
613 }
614 
616 {
617  if (for_count_ == 0)
618  throw std::runtime_error("Cannot append ENDFOR without appending a FOR first.");
619 
620  --for_count_;
621  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>("ENDFOR;");
622  commands_.push_back(cmd);
623 }
624 
625 void FanucPostProcessor::appendEndProgram(const bool call_next_program)
626 {
627  std::shared_ptr<FanucEndProgram> cmd = std::make_shared<FanucEndProgram>(call_next_program);
628  commands_.push_back(cmd);
629 }
630 
631 void FanucPostProcessor::appendCustomCommand(const std::string command)
632 {
633  std::shared_ptr<FanucStringCommand> cmd = std::make_shared<FanucStringCommand>(command + ";");
634  commands_.push_back(cmd);
635 }
636 
637 bool FanucPostProcessor::getPoseFromId(const unsigned pose_id,
638  FanucPose &pose)
639 {
640  bool found = false;
641  for (auto pose_tmp : poses_)
642  {
643  if (pose_tmp.pose_id_ == pose_id)
644  {
645  pose = pose_tmp;
646  found = true;
647  break;
648  }
649  }
650 
651  return found;
652 }
653 
655  const unsigned number)
656 {
657  if (!line_numbers_)
658  {
659  line.insert(0, ":");
660  return;
661  }
662 
663  if (number > 99999)
664  throw std::runtime_error("Line number exceeds 99999! Line number = " + std::to_string(number));
665 
666  std::string line_header(std::to_string(number));
667  line_header.append(":");
668 
669  int characters_to_be_added(6 - line_header.size());
670  if (characters_to_be_added < 0)
671  throw std::runtime_error("Error computing line number characters");
672 
673  for (unsigned i(0); i < (unsigned)characters_to_be_added; ++i)
674  line_header.insert(0, " ");
675 
676  line.insert(0, line_header);
677 }
678 
680  const unsigned number)
681 {
682  std::string twk_name(name);
683  unsigned digit_count(std::to_string(number).size());
684  if (digit_count > program_name_max_size_)
685  return false;
686 
687  int offset(0);
688  while (twk_name.size() + digit_count + offset > program_name_max_size_)
689  --offset;
690 
691  if (offset < 0)
692  twk_name.erase(twk_name.size() + offset, -offset);
693  twk_name.append(std::to_string(number));
694 
695  name = twk_name;
696  return true;
697 }
698 
699 }
Fanuc post-processor.
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 appendTimerStart(const unsigned id)
void appendCustomCommand(const std::string command)
string cmd
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)
unsigned pose_id_
Definition: pose.hpp:122
void appendLabel(const unsigned id)
std::vector< FanucGroup > groups_
Definition: pose.hpp:133
void setProgramName(ProgramName name)
std::string ProgramText
void appendDigitalOutput(const unsigned digital_out_id, const bool state)
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_
ValueType getInfo(CURLINFO key, ValueType const &defaultValue=ValueType())
Definition: curlite.hpp:343
std::string ProgramName
bool hasSameGroupsAxes(const FanucPose &other) const
Definition: pose.cpp:93
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)
bool set(CURLoption opt, ValueType value)
Definition: curlite.hpp:297
#define ROS_INFO_STREAM(args)
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)
bool isValid() const
Definition: pose.cpp:115
void appendTrackDPM(const unsigned number)


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