Skip to content

Commit ac6e629

Browse files
livanov93AndyZe
andauthored
Update hardware interface for ROS2 (#8)
* Declare all functions of the system interface. Export plugin. * Add basic definitions for base methods. * Add name getter. * Implement dummy start and stop. Add urcl driver. * Add todos in the imlementations. * Set to unique pointer for driver and dashboard. Add dashboard client within ur hw interface. * Add basic communication with driver. * Fix clang-tidy. * Add testing files for ros2_control and ros2_controllers specific PRS. * Make xacro property propagate to robot_description (#9) * Add robot_description parsing via xacro in launch file. Remove decimal places for limits. * Remove old commented urdf parsing. * Remove empty line. * Change xacro files. * Adapt launch file to new urdf folder. * Alphabetize Python imports Co-authored-by: AndyZe <[email protected]> * Revert "Make xacro property propagate to robot_description (#9)" This reverts commit 1ce877c. * Make dashboard client separate node. * Update test launch file. * Add parameters to system hw interface. * Update includes and namespace with ros2_control newest merge. * Add all state and command interfaces. * Add reading and writing. Add driver initialization. Add parameter fetching. * Set robot ip parameter for dashboard client launching. * include/ur_robot_driver/hardware_interface.h * Clang format. * Clang tidy stuff. * Remove unreachable code. * Add true limits to ros2 control xacro. * Update to recent ros2 control namespace. * Comment velocity commands. * Add tool communication parameters and class. * Add checks in configure method. * Add dashboard client node into launch file. * Add reading other stuff which should be propagated to higher level components. * Clang format. * Leave only keepalive write. * Add lambdas for detection of active controller. * Add a functor instead two different lambdas. * Fix controller decision. * Set ros2 control commit. * Prepare vectors for ft sensor and tcp pose reading. * Move information logger. * Remember old values. * Fix CI. * Move copy within successfull write. * Remove redeclaration of variable. * Make substractor only a positive value return function. * Add servo launch and configs. * Change ip. * Start comms with driver. * Add line in CMakeLists. Alphabetize header includes. * Fix method description. * Changes after review. * Create new demo subpackage. * Clang. * Install urdf folder. * Add authors. * Fix ament lint. * Fix install command format. * Add empty line. Change ip. * Remove empty lines. * Remove headless mode by default. * Fix xacro begin. * Fix install command format. * Add move group configs and launch files. Co-authored-by: AndyZe <[email protected]>
1 parent 2f8b0a1 commit ac6e629

19 files changed

+2337
-21
lines changed

ur_robot_driver/CMakeLists.txt

Lines changed: 30 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,11 @@ add_executable(dashboard_client
6868
target_link_libraries(dashboard_client ${catkin_LIBRARIES} ur_client_library::urcl)
6969
ament_target_dependencies(dashboard_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS})
7070

71+
install(
72+
TARGETS dashboard_client
73+
DESTINATION lib/${PROJECT_NAME}
74+
)
75+
7176
# add_executable(robot_state_helper
7277
# src/robot_state_helper.cpp
7378
# src/robot_state_helper_node.cpp
@@ -81,6 +86,25 @@ ament_target_dependencies(dashboard_client ${${PROJECT_NAME}_EXPORTED_TARGETS} $
8186
# RUNTIME DESTINATION bin}
8287
# )
8388

89+
# INSTALL
90+
install(
91+
TARGETS ur_robot_driver_plugin
92+
DESTINATION lib
93+
)
94+
install(
95+
DIRECTORY include/
96+
DESTINATION include
97+
)
98+
99+
100+
## EXPORTS
101+
ament_export_include_directories(
102+
include
103+
)
104+
ament_export_libraries(
105+
ur_robot_driver_plugin
106+
)
107+
84108
install(PROGRAMS scripts/tool_communication
85109
DESTINATION bin
86110
)
@@ -94,6 +118,11 @@ install(DIRECTORY include/
94118
DESTINATION include
95119
)
96120

97-
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
121+
ament_export_dependencies(
122+
hardware_interface
123+
pluginlib
124+
rclcpp
125+
${THIS_PACKAGE_INCLUDE_DEPENDS}
126+
)
98127

99128
ament_package()

ur_robot_driver/hardware_interface_plugin.xml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<library path="ur_robot_driver_plugin">
2-
<class name="ur_robot_driver/URHardwareInterface"
3-
type="ur_robot_driver::URHardwareInterface"
4-
base_class_type="hardware_interface::RobotHardwareInterface">
2+
<class name="ur_robot_driver/URPositionHardwareInterface"
3+
type="ur_robot_driver::URPositionHardwareInterface"
4+
base_class_type="hardware_interface::SystemInterface">
55
<description>
66
ROS2 Control System Driver for the Universal Robots series.
77
</description>

ur_robot_driver/include/ur_robot_driver/hardware_interface.h

Lines changed: 79 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,8 @@
1919
//----------------------------------------------------------------------
2020
/*!\file
2121
*
22-
* \author Felix Exner [email protected]
22+
* \author Lovro Ivanov [email protected]
23+
* \author Andy Zelenak [email protected]
2324
* \date 2019-04-11
2425
*
2526
*/
@@ -31,22 +32,26 @@
3132
#include <vector>
3233

3334
// ros2_control hardware_interface
35+
#include "hardware_interface/actuator.hpp"
3436
#include "hardware_interface/hardware_info.hpp"
35-
#include "hardware_interface/components/actuator.hpp"
36-
#include "hardware_interface/components/sensor.hpp"
37-
#include "hardware_interface/components/system_interface.hpp"
37+
#include "hardware_interface/sensor.hpp"
38+
#include "hardware_interface/system_interface.hpp"
3839
#include "hardware_interface/types/hardware_interface_return_values.hpp"
3940
#include "hardware_interface/types/hardware_interface_status_values.hpp"
4041
#include "hardware_interface/visibility_control.h"
4142

43+
// UR stuff
44+
#include <ur_client_library/ur/ur_driver.h>
45+
#include <ur_robot_driver/dashboard_client_ros.h>
46+
4247
// ROS
4348
#include "rclcpp/macros.hpp"
4449

50+
using hardware_interface::Actuator;
4551
using hardware_interface::HardwareInfo;
4652
using hardware_interface::return_type;
53+
using hardware_interface::Sensor;
4754
using hardware_interface::status;
48-
using hardware_interface::components::Actuator;
49-
using hardware_interface::components::Sensor;
5055

5156
namespace ur_robot_driver
5257
{
@@ -55,26 +60,90 @@ namespace ur_robot_driver
5560
* driver. It contains the read and write methods of the main control loop and registers various ROS
5661
* topics and services.
5762
*/
58-
class URHardwareInterface : public hardware_interface::components::SystemInterface
63+
class URPositionHardwareInterface : public hardware_interface::SystemInterface
5964
{
6065
public:
61-
RCLCPP_SHARED_PTR_DEFINITIONS(URHardwareInterface);
66+
RCLCPP_SHARED_PTR_DEFINITIONS(URPositionHardwareInterface);
67+
68+
return_type configure(const HardwareInfo& system_info) final;
6269

63-
hardware_interface::return_type configure(const HardwareInfo& system_info) final;
70+
std::vector<hardware_interface::StateInterface> export_state_interfaces() final;
71+
72+
std::vector<hardware_interface::CommandInterface> export_command_interfaces() final;
6473

6574
status get_status() const final
6675
{
6776
return status_;
6877
}
6978

79+
std::string get_name() const final
80+
{
81+
return info_.name;
82+
}
83+
7084
return_type start() final;
7185
return_type stop() final;
7286
return_type read() final;
7387
return_type write() final;
7488

89+
/*!
90+
* \brief Callback to handle a change in the current state of the URCaps program running on the
91+
* robot. Executed only on the state change.
92+
*
93+
* \param program_running True when the URCap program is running on the robot.
94+
*/
95+
void handleRobotProgramState(bool program_running);
96+
7597
protected:
98+
template <typename T>
99+
void readData(const std::unique_ptr<urcl::rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
100+
T& data);
101+
template <typename T, size_t N>
102+
void readBitsetData(const std::unique_ptr<urcl::rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
103+
std::bitset<N>& data);
104+
76105
HardwareInfo info_;
77106
status status_;
78-
std::vector<double> joint_angle_commands_, current_joint_angles_;
107+
108+
urcl::vector6d_t urcl_position_commands_;
109+
urcl::vector6d_t urcl_position_commands_old_;
110+
urcl::vector6d_t urcl_velocity_commands_;
111+
urcl::vector6d_t urcl_velocity_commands_old_;
112+
urcl::vector6d_t urcl_joint_positions_;
113+
urcl::vector6d_t urcl_joint_velocities_;
114+
urcl::vector6d_t urcl_joint_efforts_;
115+
urcl::vector6d_t urcl_ft_sensor_measurements_;
116+
urcl::vector6d_t urcl_tcp_pose_;
117+
bool packet_read_;
118+
119+
uint32_t runtime_state_;
120+
121+
std::bitset<18> actual_dig_out_bits_;
122+
std::bitset<18> actual_dig_in_bits_;
123+
std::array<double, 2> standard_analog_input_;
124+
std::array<double, 2> standard_analog_output_;
125+
std::bitset<4> analog_io_types_;
126+
uint32_t tool_mode_;
127+
std::bitset<2> tool_analog_input_types_;
128+
std::array<double, 2> tool_analog_input_;
129+
int32_t tool_output_voltage_;
130+
double tool_output_current_;
131+
double tool_temperature_;
132+
double speed_scaling_;
133+
double target_speed_fraction_;
134+
double speed_scaling_combined_;
135+
int32_t robot_mode_;
136+
int32_t safety_mode_;
137+
std::bitset<4> robot_status_bits_;
138+
std::bitset<11> safety_status_bits_;
139+
140+
bool robot_program_running_;
141+
bool non_blocking_read_;
142+
143+
std::unique_ptr<urcl::UrDriver> ur_driver_;
79144
};
80145
} // namespace ur_robot_driver
146+
147+
#include "pluginlib/class_list_macros.hpp"
148+
149+
PLUGINLIB_EXPORT_CLASS(ur_robot_driver::URPositionHardwareInterface, hardware_interface::SystemInterface)
Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
from launch import LaunchDescription
2+
from launch_ros.actions import Node
3+
4+
def generate_launch_description():
5+
return LaunchDescription([
6+
Node(
7+
package="ur_robot_driver",
8+
executable="dashboard_client",
9+
name="dashboard_client",
10+
output="screen",
11+
emulate_tty=True,
12+
parameters=[
13+
{"robot_ip": "10.0.1.186"}
14+
]
15+
)
16+
])

ur_robot_driver/src/dashboard_client_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,8 @@ int main(int argc, char** argv)
3434
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("ur_dashboard_client");
3535

3636
// The IP address under which the robot is reachable.
37-
const std::string robot_ip = node->declare_parameter<std::string>("robot_ip", "192.168.56.101");
37+
std::string robot_ip = node->declare_parameter<std::string>("robot_ip", "192.168.56.101");
38+
node->get_parameter<std::string>("robot_ip", robot_ip);
3839

3940
ur_robot_driver::DashboardClientROS client(node, robot_ip);
4041

0 commit comments

Comments
 (0)