28 #ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED 29 #define UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED 97 UrDriver(
const std::string& robot_ip,
const std::string& script_file,
const std::string& output_recipe_file,
98 const std::string& input_recipe_file, std::function<
void(
bool)> handle_program_state,
bool headless_mode,
99 std::unique_ptr<ToolCommSetup> tool_comm_setup,
const uint32_t reverse_port = 50001,
100 const uint32_t script_sender_port = 50002,
int servoj_gain = 2000,
double servoj_lookahead_time = 0.03,
101 bool non_blocking_read =
false,
const std::string& reverse_ip =
"",
const uint32_t trajectory_port = 50003,
102 const uint32_t script_command_port = 50004,
double force_mode_damping = 0.025,
103 double force_mode_gain_scaling = 0.5);
134 UrDriver(
const std::string& robot_ip,
const std::string& script_file,
const std::string& output_recipe_file,
135 const std::string& input_recipe_file, std::function<
void(
bool)> handle_program_state,
bool headless_mode,
136 std::unique_ptr<ToolCommSetup> tool_comm_setup,
const std::string& calibration_checksum =
"",
137 const uint32_t reverse_port = 50001,
const uint32_t script_sender_port = 50002,
int servoj_gain = 2000,
138 double servoj_lookahead_time = 0.03,
bool non_blocking_read =
false,
const std::string& reverse_ip =
"",
139 const uint32_t trajectory_port = 50003,
const uint32_t script_command_port = 50004,
140 double force_mode_damping = 0.025,
double force_mode_gain_scaling = 0.5);
170 UrDriver(
const std::string& robot_ip,
const std::string& script_file,
const std::string& output_recipe_file,
171 const std::string& input_recipe_file, std::function<
void(
bool)> handle_program_state,
bool headless_mode,
172 const std::string& calibration_checksum =
"",
const uint32_t reverse_port = 50001,
173 const uint32_t script_sender_port = 50002,
int servoj_gain = 2000,
double servoj_lookahead_time = 0.03,
174 bool non_blocking_read =
false,
const std::string& reverse_ip =
"",
const uint32_t trajectory_port = 50003,
175 const uint32_t script_command_port = 50004,
double force_mode_damping = 0.025,
176 double force_mode_gain_scaling = 0.5)
177 :
UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
178 std::unique_ptr<
ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port, servoj_gain,
179 servoj_lookahead_time, non_blocking_read, reverse_ip, trajectory_port, script_command_port,
180 force_mode_damping, force_mode_gain_scaling)
222 const float blend_radius = 0.052);
235 const vector6d_t& accelerations,
const float goal_time = 0.0);
247 const float goal_time = 0.0);
268 const int point_number = 0);
331 const unsigned int type,
const vector6d_t& limits);
498 #endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
std::unique_ptr< control::ReverseInterface > reverse_interface_
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 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, const std::string &reverse_ip="", const uint32_t trajectory_port=50003, const uint32_t script_command_port=50004, double force_mode_damping=0.025, double force_mode_gain_scaling=0.5)
Constructs a new UrDriver object. Upon initialization this class will check the calibration checksum ...
This is the main class for interfacing the driver.
ToolVoltage
Possible values for the tool voltage.
TrajectoryResult
Types for encoding trajectory execution result.
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_
FreedriveControlMessage
Control messages for starting and stopping freedrive mode.
std::string readScriptFile(const std::string &filename)
std::vector< std::string > getRTDEOutputRecipe()
Getter for the RTDE output recipe used in the RTDE client.
bool sendRobotProgram()
Sends the external control program to the robot.
bool endToolContact()
This will stop the robot from looking for a tool contact, it will also enable sending move commands t...
bool writeTrajectorySplinePoint(const vector6d_t &positions, const vector6d_t &velocities, const vector6d_t &accelerations, const float goal_time=0.0)
Writes a trajectory spline point for quintic spline interpolation onto the dedicated socket...
std::array< double, 3 > vector3d_t
void startRTDECommunication()
Starts the RTDE communication.
bool setPayload(const float mass, const vector3d_t &cog)
Set the payload mass and center of gravity. Note: It requires the external control script to be runni...
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...
std::unique_ptr< control::ScriptSender > script_sender_
const VersionInformation & getVersion()
Returns version information about the currently connected robot.
std::function< void(bool)> handle_program_state_
std::unique_ptr< control::ScriptCommandInterface > script_command_interface_
std::unique_ptr< control::TrajectoryPointInterface > trajectory_interface_
void registerToolContactResultCallback(std::function< void(control::ToolContactResult)> tool_contact_result_cb)
Register a callback for the robot-based tool contact execution completion.
rtde_interface::RTDEWriter & getRTDEWriter()
Getter for the RTDE writer used to write to the robot's RTDE interface.
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, const std::string &reverse_ip="", const uint32_t trajectory_port=50003, const uint32_t script_command_port=50004, double force_mode_damping=0.025, double force_mode_gain_scaling=0.5)
Constructs a new UrDriver object.
Parent class for notifiers.
std::string full_robot_program_
bool writeKeepalive()
Write a keepalive signal only.
uint32_t getControlFrequency() const
bool sendScript(const std::string &program)
Sends a custom script program to the robot.
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > primary_stream_
bool setToolVoltage(const ToolVoltage voltage)
Set the tool voltage. Note: It requires the external control script to be running or the robot to be ...
virtual ~UrDriver()=default
bool zeroFTSensor()
Zero the force torque sensor (only availbe on e-Series). Note: It requires the external control scrip...
ControlMode
Control modes as interpreted from the script runnning on the robot.
bool startForceMode(const vector6d_t &task_frame, const vector6uint32_t &selection_vector, const vector6d_t &wrench, const unsigned int type, const vector6d_t &limits)
Start the robot to be controlled in force mode.
std::unique_ptr< rtde_interface::DataPackage > getDataPackage()
Access function to receive the latest data package sent from the robot through RTDE interface...
bool writeTrajectoryPoint(const vector6d_t &positions, const bool cartesian, const float goal_time=0.0, const float blend_radius=0.052)
Writes a trajectory point onto the dedicated socket.
bool startToolContact()
This will make the robot look for tool contact in the tcp directions that the robot is currently movi...
std::unique_ptr< rtde_interface::RTDEClient > rtde_client_
bool writeFreedriveControlMessage(const control::FreedriveControlMessage freedrive_action)
Writes a control message in freedrive mode.
TrajectoryControlMessage
Control messages for forwarding and aborting trajectories.
bool writeTrajectoryControlMessage(const control::TrajectoryControlMessage trajectory_action, const int point_number=0)
Writes a control message in trajectory forward mode.
bool checkCalibration(const std::string &checksum)
Checks if the kinematics information in the used model fits the actual robot.
double servoj_lookahead_time_
ToolContactResult
Types for encoding until tool contact execution result.
std::array< uint32_t, 6 > vector6uint32_t
std::array< double, 6 > vector6d_t
void registerTrajectoryDoneCallback(std::function< void(control::TrajectoryResult)> trajectory_done_cb)
Register a callback for the robot-based trajectory execution completion.
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > secondary_stream_
void setKeepaliveCount(const uint32_t &count)
Set the Keepalive count. This will set the number of allowed timeout reads on the robot...
bool endForceMode()
Stop force mode and put the robot into normal operation mode.