1 #ifndef FANUC_POST_PROCESSOR_HPP 2 #define FANUC_POST_PROCESSOR_HPP 56 const unsigned lines_per_program = 0);
72 const std::string ip_address,
73 const std::string port_number =
"21",
74 const std::string username =
"",
75 const std::string password =
"");
159 const double pulse_time);
198 const unsigned value);
242 const unsigned value);
260 const unsigned value);
270 const unsigned r2_id);
295 appendRun(
const std::string program_name);
334 const std::string start,
335 const std::string stop);
345 const unsigned start,
346 const unsigned stop);
369 const unsigned number);
372 const unsigned 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 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)
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)
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)
std::vector< unsigned > labels_id_
void appendTimerReset(const unsigned id)
ProgramName program_name_
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)
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)