9 permissions_(READ_WRITE),
21 const unsigned lines_per_program)
23 output_programs.clear();
25 if (lines_per_program == 1)
26 throw std::runtime_error(
"Need at least 2 instructions per program");
28 const unsigned number_of_programs(
29 lines_per_program == 0 ? 1 : std::ceil((
double)
commands_.size() / lines_per_program));
31 if (number_of_programs > 999)
32 throw std::runtime_error(
"More than 999 programs would be generated: " + std::to_string(number_of_programs));
35 unsigned program_id(0);
36 unsigned line_count(0);
38 std::map<unsigned, FanucPose> poses_in_program;
40 for (
unsigned cmd_id(0); cmd_id <
commands_.size(); ++cmd_id)
46 program.append(
"/PROG ");
50 program.append(program_name);
54 program.append(
"/ATTR");
62 if (!
poses_.empty() &&
poses_.front().groups_.size() > 4)
63 throw std::runtime_error(
"Poses have more than 4 groups");
65 std::string default_group(
"1,*,*,*,*");
70 const unsigned number_of_groups(
poses_.front().groups_.size());
73 for (
unsigned i(0); i < number_of_groups; ++i)
75 if (default_group.size() == 8)
76 default_group.append(
"1");
78 default_group.append(
"1,");
82 for (
unsigned i(0); i < 5 - number_of_groups; ++i)
84 if (default_group.size() == 8)
85 default_group.append(
"*");
87 default_group.append(
"*,");
91 program.append(
"DEFAULT_GROUP = " + default_group +
";");
97 program.append(
"/APPL\n");
103 program.append(
"/MN");
104 program.append(
"\n");
107 if (std::shared_ptr<FanucPoseCommand> pose_cmd = std::dynamic_pointer_cast<FanucPoseCommand>(
commands_.at(cmd_id)))
110 if (poses_in_program.find(pose_cmd->pose_.pose_id_) == poses_in_program.end())
113 FanucPose modified_pose(pose_cmd->pose_);
114 modified_pose.
pose_id_ = poses_in_program.size() + 1;
115 poses_in_program.insert(std::pair<unsigned, FanucPose>(pose_cmd->pose_.pose_id_, modified_pose));
119 std::string line(poses_in_program.find(pose_cmd->pose_.pose_id_)->second.getMainLineString());
121 program.append(line);
123 else if (std::shared_ptr<FanucEndProgram> end_cmd = std::dynamic_pointer_cast<FanucEndProgram>(
commands_.at(cmd_id)))
125 if (end_cmd->call_next_)
131 std::string call_line(
"CALL " + next_program_name +
" ;\n");
133 program.append(call_line);
137 program.append(
"/POS");
138 program.append(
"\n");
140 for (
auto pose_map : poses_in_program)
141 program.append(pose_map.second.getPoseLinesString());
144 program.append(
"/END\n\n");
146 output_programs.push_back(
FanucProgram(program_name, program));
150 poses_in_program.clear();
153 else if (std::shared_ptr<FanucStringCommand> str_cmd = std::dynamic_pointer_cast<FanucStringCommand>(
156 std::string line(str_cmd->cmd_);
158 program.append(line);
161 throw std::runtime_error(
"Un-recognized FanucCommand!");
163 program.append(
"\n");
166 if (lines_per_program != 0 && line_count == lines_per_program - 1)
176 std::string call_line(
"CALL " + next_program_name +
" ;\n");
178 program.append(call_line);
181 program.append(
"/POS");
182 program.append(
"\n");
184 for (
auto pose_map : poses_in_program)
185 program.append(pose_map.second.getPoseLinesString());
188 program.append(
"/END\n\n");
190 output_programs.push_back(
FanucProgram(program_name, program));
194 poses_in_program.clear();
200 return output_programs.size();
204 program.append(
"/POS");
205 program.append(
"\n");
207 for (
auto pose_map : poses_in_program)
208 program.append(pose_map.second.getPoseLinesString());
211 program.append(
"/END\n\n");
212 output_programs.push_back(
FanucProgram(program_name, program));
213 return output_programs.size();
229 const std::string ip_address,
230 const std::string port_number,
231 const std::string username,
232 const std::string password)
235 for (
auto &program : programs)
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");
242 ls_program << program.second;
246 ROS_INFO_STREAM(
"Trying to upload " + program.first +
".ls at " + ip_address);
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);
256 std::ifstream ifs(
"/tmp/" + program.first +
".ls", std::ios::binary);
259 double total_secs = curlite.
getInfo<
double>(CURLINFO_TOTAL_TIME);
262 catch (std::exception &e)
264 throw std::runtime_error(e.what());
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");
300 throw std::runtime_error(
"Pose is not valid");
303 throw std::runtime_error(
"Pose does not have the same groups/axes of the first pose in the program");
311 std::shared_ptr<FanucPoseCommand>
cmd = std::make_shared<FanucPoseCommand>(pose);
319 throw std::runtime_error(
"Invalid pose id (0)");
321 for (
auto pose_tmp :
poses_)
323 if (pose_tmp.pose_id_ == pose.
pose_id_)
326 std::shared_ptr<FanucPoseCommand>
cmd = std::make_shared<FanucPoseCommand>(pose);
327 cmd->pose_.groups_ = pose_tmp.groups_;
329 if (!cmd->pose_.isValid())
330 throw std::runtime_error(
"Pose is not valid");
337 throw std::runtime_error(
"Pose ID " + std::to_string(pose.
pose_id_) +
" was not found");
342 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"!" + comment +
";");
348 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
";");
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 +
";");
362 const double pulse_time)
365 throw std::runtime_error(
"Pulse time must be > 0");
367 const std::string digital_output_id(std::to_string(digital_out_id));
368 std::ostringstream ss;
369 ss.imbue(std::locale(
"C"));
370 ss << std::fixed << std::setprecision(2);
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;");
381 throw std::runtime_error(
"Time must be >= 0");
383 std::ostringstream ss;
384 ss.imbue(std::locale(
"C"));
385 ss << std::fixed << std::setprecision(2);
387 const std::string duration = ss.str();
388 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"WAIT " + duration +
"(sec);");
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) +
"];");
402 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"Track End;");
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 +
";");
417 const unsigned value)
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 +
";");
429 throw std::runtime_error(
"Timer ID must be > 0");
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;");
440 throw std::runtime_error(
"Timer ID must be > 0");
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;");
451 throw std::runtime_error(
"Timer ID must be > 0");
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;");
462 throw std::runtime_error(
"UFrame number exceeds maximum of 9, UFrame ID given = " + std::to_string(uf_id));
464 const std::string uframe(std::to_string(uf_id));
465 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"UFRAME_NUM=" + uframe +
";");
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));
474 const std::string utool(std::to_string(ut_id));
475 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"UTOOL_NUM=" + utool +
";");
480 const unsigned value)
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 +
";");
493 throw std::runtime_error(
"Register ID starts at 1. Given register ID = 0");
495 const std::string id(std::to_string(r_id));
496 std::ostringstream ss;
497 ss.imbue(std::locale(
"C"));
498 ss << std::fixed << std::setprecision(2);
500 const std::string r_value = ss.str();
501 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"R[" +
id +
"]=" + r_value +
";");
506 const unsigned value)
509 throw std::runtime_error(
"Register ID starts at 1. Given register ID = 0");
511 const std::string id(std::to_string(r_id));
512 std::ostringstream ss;
514 const std::string r_value = ss.str();
515 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"R[" +
id +
"]=" + r_value +
";");
520 const unsigned r2_id)
523 throw std::runtime_error(
"Register ID starts at 1. Given register 1 ID = 0");
525 throw std::runtime_error(
"Register ID starts at 1. Given register 2 ID = 0");
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 +
"];");
537 throw std::runtime_error(
"Flags ID starts at 1. Given register ID = 0");
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 +
");");
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 +
";");
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 +
";");
564 for (std::vector<unsigned>::iterator iter(
labels_id_.begin()); iter !=
labels_id_.end(); ++iter)
566 throw std::runtime_error(
"Label ID does not exist. Given label ID = " + std::to_string(
id));
569 const std::string lbl_id(std::to_string(
id));
570 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"LBL[" + lbl_id +
"];");
577 const std::string lbl_id(std::to_string(
id));
578 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"JMP LBL[" + lbl_id +
"];");
584 const std::string datamon_id(std::to_string(
id));
585 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"Sample Start[" + datamon_id +
"];");
591 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"Sample End;");
596 const std::string start,
597 const std::string stop)
599 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
600 "FOR R[" + std::to_string(reg_id) +
"]=" + start +
" TO " + stop +
";");
606 const unsigned start,
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) +
";");
618 throw std::runtime_error(
"Cannot append ENDFOR without appending a FOR first.");
621 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(
"ENDFOR;");
627 std::shared_ptr<FanucEndProgram>
cmd = std::make_shared<FanucEndProgram>(call_next_program);
633 std::shared_ptr<FanucStringCommand>
cmd = std::make_shared<FanucStringCommand>(command +
";");
641 for (
auto pose_tmp :
poses_)
643 if (pose_tmp.pose_id_ == pose_id)
655 const unsigned number)
664 throw std::runtime_error(
"Line number exceeds 99999! Line number = " + std::to_string(number));
666 std::string line_header(std::to_string(number));
667 line_header.append(
":");
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");
673 for (
unsigned i(0); i < (unsigned)characters_to_be_added; ++i)
674 line_header.insert(0,
" ");
676 line.insert(0, line_header);
680 const unsigned number)
682 std::string twk_name(name);
683 unsigned digit_count(std::to_string(number).size());
692 twk_name.erase(twk_name.size() + offset, -offset);
693 twk_name.append(std::to_string(number));
void uploadToFtp(const FanucPrograms programs, const std::string ip_address, const std::string port_number="21", const std::string username="", const std::string password="")
void appendGroupOutput(const unsigned id, const unsigned value)
void appendCall(const std::string program_name)
void appendSetFlag(const unsigned f_id, const bool value)
void appendComment(const std::string comment)
void setPermissions(const FanucPostProcessor::Permissions perms)
FanucPostProcessor()
Default Constructor.
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)
void appendPose(FanucPose &pose)
std::string program_comment_
void appendPoseId(FanucPose &pose)
void appendJumpLabel(const unsigned id)
void appendLabel(const unsigned id)
std::vector< FanucGroup > groups_
void setProgramName(ProgramName name)
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)
std::vector< unsigned > labels_id_
void appendTimerReset(const unsigned id)
ProgramName program_name_
ValueType getInfo(CURLINFO key, ValueType const &defaultValue=ValueType())
bool hasSameGroupsAxes(const FanucPose &other) const
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)
#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)
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)
FanucPostProcessor::Permissions permissions_
void appendDataMonitorStop()
void appendTimerStop(const unsigned id)
void appendTrackDPM(const unsigned number)