Skip to content

Commit 7443b54

Browse files
committed
Merge branch 'main' into tool_contact
2 parents baa9f7c + 14f80ac commit 7443b54

21 files changed

+473
-117
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -115,7 +115,7 @@ For getting started, you'll basically need three steps:
115115
details.
116116

117117
```bash
118-
# Replace ur5e with one of ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e, ur20, ur30
118+
# Replace ur5e with one of ur3, ur3e, ur5, ur5e, ur7e, ur10, ur10e, ur12e, ur16e, ur20, ur30
119119
# Replace the IP address with the IP address of your actual robot / URSim
120120
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=192.168.56.101
121121
```

ur_controllers/include/ur_controllers/passthrough_trajectory_controller.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -81,6 +81,7 @@ namespace ur_controllers
8181
* 5.0: The robot finished executing the trajectory.
8282
*/
8383
const double TRANSFER_STATE_IDLE = 0.0;
84+
const double TRANSFER_STATE_NEW_TRAJECTORY = 6.0;
8485
const double TRANSFER_STATE_WAITING_FOR_POINT = 1.0;
8586
const double TRANSFER_STATE_TRANSFERRING = 2.0;
8687
const double TRANSFER_STATE_TRANSFER_DONE = 3.0;
@@ -174,6 +175,7 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
174175

175176
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>> scaling_state_interface_;
176177
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> abort_command_interface_;
178+
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> trajectory_size_command_interface_;
177179
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> transfer_command_interface_;
178180
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> time_from_start_command_interface_;
179181

ur_controllers/src/passthrough_trajectory_controller.cpp

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -132,6 +132,7 @@ controller_interface::InterfaceConfiguration PassthroughTrajectoryController::co
132132
config.names.push_back(tf_prefix + "trajectory_passthrough/abort");
133133
config.names.emplace_back(tf_prefix + "trajectory_passthrough/transfer_state");
134134
config.names.emplace_back(tf_prefix + "trajectory_passthrough/time_from_start");
135+
config.names.emplace_back(tf_prefix + "trajectory_passthrough/trajectory_size");
135136

136137
return config;
137138
}
@@ -180,6 +181,19 @@ controller_interface::CallbackReturn PassthroughTrajectoryController::on_activat
180181
}
181182
}
182183

184+
{
185+
const std::string interface_name = passthrough_params_.tf_prefix + "trajectory_passthrough/"
186+
"trajectory_size";
187+
auto it = std::find_if(command_interfaces_.begin(), command_interfaces_.end(),
188+
[&](auto& interface) { return (interface.get_name() == interface_name); });
189+
if (it != command_interfaces_.end()) {
190+
trajectory_size_command_interface_ = *it;
191+
} else {
192+
RCLCPP_ERROR(get_node()->get_logger(), "Did not find '%s' in command interfaces.", interface_name.c_str());
193+
return controller_interface::CallbackReturn::ERROR;
194+
}
195+
}
196+
183197
const std::string tf_prefix = passthrough_params_.tf_prefix;
184198
{
185199
const std::string interface_name = tf_prefix + "trajectory_passthrough/transfer_state";
@@ -254,7 +268,9 @@ controller_interface::return_type PassthroughTrajectoryController::update(const
254268
active_trajectory_elapsed_time_ = rclcpp::Duration(0, 0);
255269
max_trajectory_time_ =
256270
rclcpp::Duration::from_seconds(duration_to_double(active_joint_traj_.points.back().time_from_start));
257-
write_success &= transfer_command_interface_->get().set_value(TRANSFER_STATE_WAITING_FOR_POINT);
271+
write_success &= transfer_command_interface_->get().set_value(TRANSFER_STATE_NEW_TRAJECTORY);
272+
write_success &=
273+
trajectory_size_command_interface_->get().set_value(static_cast<double>(active_joint_traj_.points.size()));
258274
}
259275
auto active_goal_time_tol = goal_time_tolerance_.readFromRT();
260276
auto joint_mapping = joint_trajectory_mapping_.readFromRT();

ur_moveit_config/launch/ur_moveit.launch.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,8 +73,10 @@ def declare_arguments():
7373
"ur3e",
7474
"ur5",
7575
"ur5e",
76+
"ur7e",
7677
"ur10",
7778
"ur10e",
79+
"ur12e",
7880
"ur16e",
7981
"ur20",
8082
"ur30",

ur_robot_driver/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -102,6 +102,7 @@ ament_target_dependencies(controller_stopper_node ${${PROJECT_NAME}_EXPORTED_TAR
102102
add_executable(robot_state_helper
103103
src/robot_state_helper.cpp
104104
src/robot_state_helper_node.cpp
105+
src/urcl_log_handler.cpp
105106
)
106107
target_link_libraries(robot_state_helper ur_client_library::urcl)
107108
ament_target_dependencies(robot_state_helper ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS})

ur_robot_driver/doc/usage/startup.rst

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,8 @@ nodes for UR robots. The only required arguments are the ``ur_type`` and ``robot
2222
2323
$ ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=192.168.56.101
2424
25-
Allowed ``ur_type`` strings: ``ur3``, ``ur3e``, ``ur5``, ``ur5e``, ``ur10``, ``ur10e``, ``ur16e``,
26-
``ur20``, ``ur30``.
25+
Allowed ``ur_type`` strings: ``ur3``, ``ur3e``, ``ur5``, ``ur5e``, ``ur7e``, ``ur10``, ``ur10e``,
26+
``ur12e``, ``ur16e``, ``ur20``, ``ur30``.
2727

2828
Other important arguments are:
2929

ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@
5151
// UR client library
5252
#include "ur_client_library/ur/dashboard_client.h"
5353
#include "ur_client_library/exceptions.h"
54-
#include "ur_dashboard_msgs/msg/program_state.hpp"
54+
#include "ur_client_library/primary/primary_client.h"
5555
#include "ur_dashboard_msgs/srv/add_to_log.hpp"
5656
#include "ur_dashboard_msgs/srv/get_loaded_program.hpp"
5757
#include "ur_dashboard_msgs/srv/get_program_state.hpp"
@@ -120,6 +120,9 @@ class DashboardClientROS
120120
std::shared_ptr<rclcpp::Node> node_;
121121
urcl::DashboardClient client_;
122122

123+
urcl::comm::INotifier notifier_;
124+
urcl::primary_interface::PrimaryClient primary_client_;
125+
123126
// Commanding services
124127
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr brake_release_service_;
125128
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr clear_operational_mode_service_;

ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -168,8 +168,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
168168
void stop_force_mode();
169169
void check_passthrough_trajectory_controller();
170170
void trajectory_done_callback(urcl::control::TrajectoryResult result);
171-
bool has_accelerations(std::vector<std::array<double, 6>> accelerations);
172-
bool has_velocities(std::vector<std::array<double, 6>> velocities);
171+
bool is_valid_joint_information(std::vector<std::array<double, 6>> data);
173172
void tool_contact_callback(urcl::control::ToolContactResult);
174173
void check_tool_contact_controller();
175174

@@ -249,6 +248,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
249248
// Passthrough trajectory controller interface values
250249
double passthrough_trajectory_transfer_state_;
251250
double passthrough_trajectory_abort_;
251+
double passthrough_trajectory_size_;
252252
bool passthrough_trajectory_controller_running_;
253253
urcl::vector6d_t passthrough_trajectory_positions_;
254254
urcl::vector6d_t passthrough_trajectory_velocities_;

ur_robot_driver/include/ur_robot_driver/robot_state_helper.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
#ifndef UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_
3030
#define UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_
3131

32-
#include <chrono>
32+
#include <string>
3333
#include <memory>
3434

3535
#include "rclcpp/rclcpp.hpp"
@@ -41,6 +41,7 @@
4141
#include "ur_dashboard_msgs/msg/safety_mode.hpp"
4242
#include "ur_dashboard_msgs/msg/robot_mode.hpp"
4343
#include "ur_client_library/ur/datatypes.h"
44+
#include "ur_client_library/primary/primary_client.h"
4445

4546
namespace ur_robot_driver
4647
{
@@ -90,6 +91,10 @@ class RobotStateHelper
9091
std::atomic<bool> program_running_;
9192
std::mutex goal_mutex_;
9293

94+
std::string robot_ip_;
95+
urcl::comm::INotifier notifier_;
96+
std::shared_ptr<urcl::primary_interface::PrimaryClient> primary_client_;
97+
9398
rclcpp_action::Server<ur_dashboard_msgs::action::SetMode>::SharedPtr set_mode_as_;
9499

95100
rclcpp::CallbackGroup::SharedPtr robot_mode_sub_cb_;
@@ -100,12 +105,7 @@ class RobotStateHelper
100105

101106
rclcpp::CallbackGroup::SharedPtr service_cb_grp_;
102107

103-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr unlock_protective_stop_srv_;
104108
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr restart_safety_srv_;
105-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr power_on_srv_;
106-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr power_off_srv_;
107-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr brake_release_srv_;
108-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr stop_program_srv_;
109109
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr play_program_srv_;
110110
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr resend_robot_program_srv_;
111111
};
Lines changed: 101 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,101 @@
1+
# Copyright (c) 2025 Universal Robots A/S
2+
#
3+
# Redistribution and use in source and binary forms, with or without
4+
# modification, are permitted provided that the following conditions are met:
5+
#
6+
# * Redistributions of source code must retain the above copyright
7+
# notice, this list of conditions and the following disclaimer.
8+
#
9+
# * Redistributions in binary form must reproduce the above copyright
10+
# notice, this list of conditions and the following disclaimer in the
11+
# documentation and/or other materials provided with the distribution.
12+
#
13+
# * Neither the name of the {copyright_holder} nor the names of its
14+
# contributors may be used to endorse or promote products derived from
15+
# this software without specific prior written permission.
16+
#
17+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
# POSSIBILITY OF SUCH DAMAGE.
28+
29+
from launch import LaunchDescription
30+
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
31+
from launch.launch_description_sources import PythonLaunchDescriptionSource
32+
from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir
33+
34+
35+
def generate_launch_description():
36+
# Declare arguments
37+
declared_arguments = []
38+
declared_arguments.append(
39+
DeclareLaunchArgument(
40+
"robot_ip",
41+
description="IP address by which the robot can be reached.",
42+
)
43+
)
44+
declared_arguments.append(
45+
DeclareLaunchArgument(
46+
"use_mock_hardware",
47+
default_value="false",
48+
description="Start robot with mock hardware mirroring command to its states.",
49+
)
50+
)
51+
declared_arguments.append(
52+
DeclareLaunchArgument(
53+
"mock_sensor_commands",
54+
default_value="false",
55+
description="Enable mock command interfaces for sensors used for simple simulations. "
56+
"Used only if 'use_mock_hardware' parameter is true.",
57+
)
58+
)
59+
declared_arguments.append(
60+
DeclareLaunchArgument(
61+
"initial_joint_controller",
62+
default_value="scaled_joint_trajectory_controller",
63+
description="Initially loaded robot controller.",
64+
choices=[
65+
"scaled_joint_trajectory_controller",
66+
"joint_trajectory_controller",
67+
"forward_velocity_controller",
68+
"forward_position_controller",
69+
"freedrive_mode_controller",
70+
"passthrough_trajectory_controller",
71+
],
72+
)
73+
)
74+
declared_arguments.append(
75+
DeclareLaunchArgument(
76+
"activate_joint_controller",
77+
default_value="true",
78+
description="Activate loaded joint controller.",
79+
)
80+
)
81+
82+
# Initialize Arguments
83+
robot_ip = LaunchConfiguration("robot_ip")
84+
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
85+
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
86+
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
87+
activate_joint_controller = LaunchConfiguration("activate_joint_controller")
88+
89+
base_launch = IncludeLaunchDescription(
90+
PythonLaunchDescriptionSource([ThisLaunchFileDir(), "/ur_control.launch.py"]),
91+
launch_arguments={
92+
"ur_type": "ur12e",
93+
"robot_ip": robot_ip,
94+
"use_mock_hardware": use_mock_hardware,
95+
"mock_sensor_commands": mock_sensor_commands,
96+
"initial_joint_controller": initial_joint_controller,
97+
"activate_joint_controller": activate_joint_controller,
98+
}.items(),
99+
)
100+
101+
return LaunchDescription(declared_arguments + [base_launch])

0 commit comments

Comments
 (0)