1 #ifndef FANUC_POST_PROCESSOR_HPP 2 #define FANUC_POST_PROCESSOR_HPP 63 unsigned generatePrograms(std::vector<std::pair<ProgramName, Program>> &output_programs,
64 const unsigned lines_per_program = 0);
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 =
"");
167 const double pulse_time);
207 const unsigned value);
232 appendRun(
const std::string program_name);
271 const std::string start,
272 const std::string stop);
282 const unsigned start,
283 const unsigned stop);
301 const unsigned number);
304 const unsigned number);
void appendGroupOutput(const unsigned id, const unsigned value)
void appendCall(const std::string program_name)
void appendComment(const std::string comment)
void setPermissions(const FanucPostProcessor::Permissions perms)
FanucPostProcessor()
Default Constructor.
void setMemorySize(const unsigned size)
void appendCustomCommand(const std::string command)
void appendSetRegister(const unsigned r_id, const double value)
void prependLineNumber(std::string &line, const unsigned number)
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)
std::vector< unsigned > labels_id_
void setProgramName(std::string name)
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)
void appendWait(const double time)
void appendUFrame(const unsigned uf_id)
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)
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()