27 #ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED 28 #define UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED 87 UrDriver(
const std::string& robot_ip,
const std::string& script_file,
const std::string& output_recipe_file,
88 const std::string& input_recipe_file, std::function<
void(
bool)> handle_program_state,
bool headless_mode,
89 std::unique_ptr<ToolCommSetup> tool_comm_setup,
const std::string& calibration_checksum =
"",
90 const uint32_t reverse_port = 50001,
const uint32_t script_sender_port = 50002,
int servoj_gain = 2000,
91 double servoj_lookahead_time = 0.03,
bool non_blocking_read =
false);
113 UrDriver(
const std::string& robot_ip,
const std::string& script_file,
const std::string& output_recipe_file,
114 const std::string& input_recipe_file, std::function<
void(
bool)> handle_program_state,
bool headless_mode,
115 const std::string& calibration_checksum =
"",
const uint32_t reverse_port = 50001,
116 const uint32_t script_sender_port = 50002,
int servoj_gain = 2000,
double servoj_lookahead_time = 0.03,
117 bool non_blocking_read =
false)
118 :
UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
119 std::unique_ptr<
ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port, servoj_gain,
120 servoj_lookahead_time, non_blocking_read)
260 #endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED uint32_t getControlFrequency() const
This is the main class for interfacing the driver.
bool writeJointCommand(const vector6d_t &values, const comm::ControlMode control_mode)
Writes a joint command together with a keepalive signal onto the socket being sent to the robot...
comm::INotifier notifier_
VersionInformation robot_version_
std::string readScriptFile(const std::string &filename)
std::vector< std::string > getRTDEOutputRecipe()
Getter for the RTDE output recipe used in the RTDE client.
UrDriver(const std::string &robot_ip, const std::string &script_file, const std::string &output_recipe_file, const std::string &input_recipe_file, std::function< void(bool)> handle_program_state, bool headless_mode, std::unique_ptr< ToolCommSetup > tool_comm_setup, const std::string &calibration_checksum="", const uint32_t reverse_port=50001, const uint32_t script_sender_port=50002, int servoj_gain=2000, double servoj_lookahead_time=0.03, bool non_blocking_read=false)
Constructs a new UrDriver object. Upon initialization this class will check the calibration checksum ...
bool sendRobotProgram()
Sends the external control program to the robot.
void startRTDECommunication()
Starts the RTDE communication.
UrDriver(const std::string &robot_ip, const std::string &script_file, const std::string &output_recipe_file, const std::string &input_recipe_file, std::function< void(bool)> handle_program_state, bool headless_mode, const std::string &calibration_checksum="", const uint32_t reverse_port=50001, const uint32_t script_sender_port=50002, int servoj_gain=2000, double servoj_lookahead_time=0.03, bool non_blocking_read=false)
Constructs a new UrDriver object.
The RTDEWriter class offers an abstraction layer to send data to the robot via the RTDE interface...
bool stopControl()
Sends a stop command to the socket interface which will signal the program running on the robot to no...
void checkCalibration(const std::string &checksum)
Checks if the kinematics information in the used model fits the actual robot.
std::unique_ptr< comm::ReverseInterface > reverse_interface_
const VersionInformation & getVersion()
Returns version information about the currently connected robot.
std::function< void(bool)> handle_program_state_
rtde_interface::RTDEWriter & getRTDEWriter()
Getter for the RTDE writer used to write to the robot's RTDE interface.
Parent class for notifiers.
std::string full_robot_program_
bool writeKeepalive()
Write a keepalive signal only.
bool sendScript(const std::string &program)
Sends a custom script program to the robot.
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > primary_stream_
virtual ~UrDriver()=default
ControlMode
Control modes as interpreted from the script runnning on the robot.
std::unique_ptr< rtde_interface::DataPackage > getDataPackage()
Access function to receive the latest data package sent from the robot through RTDE interface...
std::unique_ptr< rtde_interface::RTDEClient > rtde_client_
double servoj_lookahead_time_
std::array< double, 6 > vector6d_t
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > secondary_stream_
std::unique_ptr< comm::ScriptSender > script_sender_
void setKeepaliveCount(const uint32_t &count)
Set the Keepalive count. This will set the number of allowed timeout reads on the robot...