Program Listing for File ur_driver.h
↰ Return to documentation for file (/tmp/ws/src/ur_client_library/include/ur_client_library/ur/ur_driver.h
)
// this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
// -- BEGIN LICENSE BLOCK ----------------------------------------------
// Copyright 2019 FZI Forschungszentrum Informatik
// Created on behalf of Universal Robots A/S
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// -- END LICENSE BLOCK ------------------------------------------------
//----------------------------------------------------------------------
//----------------------------------------------------------------------
#ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
#define UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
#include <functional>
#include "ur_client_library/rtde/rtde_client.h"
#include "ur_client_library/control/reverse_interface.h"
#include "ur_client_library/control/trajectory_point_interface.h"
#include "ur_client_library/control/script_command_interface.h"
#include "ur_client_library/control/script_sender.h"
#include "ur_client_library/ur/tool_communication.h"
#include "ur_client_library/ur/version_information.h"
#include "ur_client_library/ur/robot_receive_timeout.h"
#include "ur_client_library/primary/robot_message/version_message.h"
#include "ur_client_library/rtde/rtde_writer.h"
namespace urcl
{
class UrDriver
{
public:
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);
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, 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);
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)
: UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
std::unique_ptr<ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port, servoj_gain,
servoj_lookahead_time, non_blocking_read, reverse_ip, trajectory_port, script_command_port,
force_mode_damping, force_mode_gain_scaling)
{
}
virtual ~UrDriver() = default;
std::unique_ptr<rtde_interface::DataPackage> getDataPackage();
uint32_t getControlFrequency() const
{
return rtde_frequency_;
}
bool writeJointCommand(const vector6d_t& values, const comm::ControlMode control_mode,
const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(20));
bool writeTrajectoryPoint(const vector6d_t& positions, const bool cartesian, const float goal_time = 0.0,
const float blend_radius = 0.052);
bool writeTrajectorySplinePoint(const vector6d_t& positions, const vector6d_t& velocities,
const vector6d_t& accelerations, const float goal_time = 0.0);
bool writeTrajectorySplinePoint(const vector6d_t& positions, const vector6d_t& velocities,
const float goal_time = 0.0);
bool writeTrajectorySplinePoint(const vector6d_t& positions, const float goal_time = 0.0);
bool
writeTrajectoryControlMessage(const control::TrajectoryControlMessage trajectory_action, const int point_number = 0,
const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(200));
bool
writeFreedriveControlMessage(const control::FreedriveControlMessage freedrive_action,
const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(200));
bool zeroFTSensor();
bool setPayload(const float mass, const vector3d_t& cog);
bool setToolVoltage(const ToolVoltage voltage);
bool startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, const vector6d_t& wrench,
const unsigned int type, const vector6d_t& limits);
bool endForceMode();
bool startToolContact();
bool endToolContact();
bool writeKeepalive(const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(1000));
void startRTDECommunication();
bool stopControl();
bool checkCalibration(const std::string& checksum);
rtde_interface::RTDEWriter& getRTDEWriter();
bool sendScript(const std::string& program);
bool sendRobotProgram();
const VersionInformation& getVersion()
{
return robot_version_;
}
std::vector<std::string> getRTDEOutputRecipe();
[[deprecated("Set keepaliveCount is deprecated, instead set the robot receive timeout directly in the write "
"commands.")]] void
setKeepaliveCount(const uint32_t count);
void registerTrajectoryDoneCallback(std::function<void(control::TrajectoryResult)> trajectory_done_cb)
{
trajectory_interface_->setTrajectoryEndCallback(trajectory_done_cb);
}
void registerToolContactResultCallback(std::function<void(control::ToolContactResult)> tool_contact_result_cb)
{
script_command_interface_->setToolContactResultCallback(tool_contact_result_cb);
}
private:
static std::string readScriptFile(const std::string& filename);
int rtde_frequency_;
comm::INotifier notifier_;
std::unique_ptr<rtde_interface::RTDEClient> rtde_client_;
std::unique_ptr<control::ReverseInterface> reverse_interface_;
std::unique_ptr<control::TrajectoryPointInterface> trajectory_interface_;
std::unique_ptr<control::ScriptCommandInterface> script_command_interface_;
std::unique_ptr<control::ScriptSender> script_sender_;
std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> primary_stream_;
std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> secondary_stream_;
uint32_t servoj_gain_;
double servoj_lookahead_time_;
std::chrono::milliseconds step_time_;
std::function<void(bool)> handle_program_state_;
std::string robot_ip_;
bool in_headless_mode_;
std::string full_robot_program_;
int get_packet_timeout_;
bool non_blocking_read_;
VersionInformation robot_version_;
};
} // namespace urcl
#endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED