Skip to content

Commit 92ded2d

Browse files
authored
Trajectory until node (#1461)
The trajectory until node allows a user to execute a trajectory with an "until" condition enabled (currently only tool contact is available) without having to call 2 actions at the same time.
1 parent bcbcac7 commit 92ded2d

File tree

9 files changed

+898
-0
lines changed

9 files changed

+898
-0
lines changed

ur_robot_driver/CMakeLists.txt

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -137,12 +137,26 @@ target_link_libraries(urscript_interface PUBLIC
137137
ur_client_library::urcl
138138
)
139139

140+
#
141+
# trajectory_until_node
142+
#
143+
add_executable(trajectory_until_node
144+
src/trajectory_until_node.cpp
145+
)
146+
target_link_libraries(trajectory_until_node PUBLIC
147+
rclcpp::rclcpp
148+
${std_msgs_TARGETS}
149+
rclcpp_action::rclcpp_action
150+
${ur_msgs_TARGETS}
151+
)
152+
140153
install(
141154
TARGETS
142155
dashboard_client
143156
controller_stopper_node
144157
urscript_interface
145158
robot_state_helper
159+
trajectory_until_node
146160
DESTINATION lib/${PROJECT_NAME}
147161
)
148162

@@ -211,6 +225,7 @@ install(PROGRAMS
211225
scripts/start_ursim.sh
212226
examples/examples.py
213227
examples/force_mode.py
228+
examples/move_until_example.py
214229
DESTINATION lib/${PROJECT_NAME}
215230
)
216231

@@ -280,5 +295,9 @@ if(BUILD_TESTING)
280295
TIMEOUT
281296
800
282297
)
298+
add_launch_test(test/integration_test_trajectory_until.py
299+
TIMEOUT
300+
800
301+
)
283302
endif()
284303
endif()

ur_robot_driver/doc/index.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,3 +21,4 @@ ur_robot_driver
2121
dashboard_client
2222
robot_state_helper
2323
controller_stopper
24+
trajectory_until_node
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
.. _trajectory_until_node:
2+
3+
Trajectory until node
4+
=====================
5+
6+
The trajectory until node allows a user to execute a trajectory with an "until" condition enabled (currently only tool contact is available) without having to call 2 actions at the same time. This means that the trajectory will execute until either the trajectory is finished or the "until" condition has been triggered. Both scenarios will result in the trajectory being reported as successful.
7+
8+
Action interface / usage
9+
""""""""""""""""""""""""
10+
The node provides an action to execute a trajectory with tool contact enabled. For the node to accept action goals, both the motion controller and the tool contact controller need to be in ``active`` state.
11+
12+
* ``/trajectory_until_node/execute [ur_msgs/action/TrajectoryUntil]``
13+
14+
The action contains all the same fields as the ordinary `FollowJointTrajectory <http://docs.ros.org/en/noetic/api/control_msgs/html/action/FollowJointTrajectory.html>`_ action, but has two additional fields.
15+
One in the goal section called ``until_type``, which is used to choose between different conditions that can stop the trajectory. Currently only tool contact is available.
16+
The result section contains the other new field called ``until_condition_result``, which reports whether the chosen condition was triggered or not.
17+
18+
Implementation details
19+
""""""""""""""""""""""
20+
Upon instantiation of the node, the internal trajectory action client will connect to an action named ``motion_controller/follow_joint_trajectory``.
21+
This action does not exist, but upon launch of the driver, the node is remapped to connect to the ``initial_joint_controller``, default is ``scaled_joint_trajectory_controller``.
22+
If you wish to use the node with another motion controller use the launch argument ``initial_joint_controller:=<your_motion_controller>`` when launching the driver.
23+
The node is only compatible with motion controllers that use the FollowJointTrajectory action interface.
Lines changed: 132 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,132 @@
1+
#!/usr/bin/env python3
2+
# Copyright 2025, Universal Robots A/S
3+
#
4+
# Redistribution and use in source and binary forms, with or without
5+
# modification, are permitted provided that the following conditions are met:
6+
#
7+
# * Redistributions of source code must retain the above copyright
8+
# notice, this list of conditions and the following disclaimer.
9+
#
10+
# * Redistributions in binary form must reproduce the above copyright
11+
# notice, this list of conditions and the following disclaimer in the
12+
# documentation and/or other materials provided with the distribution.
13+
#
14+
# * Neither the name of the {copyright_holder} nor the names of its
15+
# contributors may be used to endorse or promote products derived from
16+
# this software without specific prior written permission.
17+
#
18+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
# POSSIBILITY OF SUCH DAMAGE.
29+
30+
import time
31+
32+
import rclpy
33+
from rclpy.action import ActionClient
34+
35+
from builtin_interfaces.msg import Duration
36+
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
37+
from ur_msgs.action import FollowJointTrajectoryUntil
38+
39+
ROBOT_JOINTS = [
40+
"elbow_joint",
41+
"shoulder_lift_joint",
42+
"shoulder_pan_joint",
43+
"wrist_1_joint",
44+
"wrist_2_joint",
45+
"wrist_3_joint",
46+
]
47+
48+
49+
class MoveUntilExample(rclpy.node.Node):
50+
def __init__(self):
51+
super().__init__("move_until_example")
52+
53+
self._send_goal_future = None
54+
self._get_result_future = None
55+
self._goal_handle = None
56+
self._action_client = ActionClient(
57+
self, FollowJointTrajectoryUntil, "/trajectory_until_node/execute"
58+
)
59+
self._action_client.wait_for_server()
60+
self.test_traj = {
61+
"waypts": [[1.5, -1.5, 0.0, -1.5, -1.5, -1.5], [2.1, -1.2, 0.0, -2.4, -1.5, -1.5]],
62+
"time_vec": [Duration(sec=3, nanosec=0), Duration(sec=6, nanosec=0)],
63+
}
64+
self.get_logger().info("Initialized")
65+
66+
def cancel_goal(self):
67+
if self._goal_handle is not None:
68+
self.get_logger().info("Cancelling goal")
69+
future = self._goal_handle.cancel_goal_async()
70+
future.add_done_callback(self.cancel_done)
71+
72+
def cancel_done(self, future):
73+
try:
74+
future.result()
75+
self.get_logger().info("Goal cancelled successfully")
76+
except Exception as e:
77+
self.get_logger().error(f"Failed to cancel goal: {e}")
78+
79+
def process(self):
80+
trajectory = JointTrajectory()
81+
trajectory.joint_names = ROBOT_JOINTS
82+
83+
trajectory.points = [
84+
JointTrajectoryPoint(
85+
positions=self.test_traj["waypts"][i], time_from_start=self.test_traj["time_vec"][i]
86+
)
87+
for i in range(len(self.test_traj["waypts"]))
88+
]
89+
goal = FollowJointTrajectoryUntil.Goal(
90+
trajectory=trajectory, until_type=FollowJointTrajectoryUntil.Goal.TOOL_CONTACT
91+
)
92+
self._send_goal_future = self._action_client.send_goal_async(goal)
93+
rclpy.spin_until_future_complete(self, self._send_goal_future)
94+
self._goal_handle = self._send_goal_future.result()
95+
if not self._goal_handle.accepted:
96+
self.get_logger().error("Goal rejected :(")
97+
raise RuntimeError("Goal rejected :(")
98+
99+
self.get_logger().info(
100+
f"Goal accepted with ID: {bytes(self._goal_handle.goal_id.uuid).hex()}\n"
101+
)
102+
103+
result_future = self._goal_handle.get_result_async()
104+
rclpy.spin_until_future_complete(self, result_future)
105+
result = result_future.result().result
106+
print(result)
107+
if result is None:
108+
self.get_logger().error("Result is None")
109+
return
110+
if result.error_code != FollowJointTrajectoryUntil.Result.SUCCESSFUL:
111+
self.get_logger().error(f"Result error code: {result.error_code}")
112+
return
113+
if result.until_condition_result == FollowJointTrajectoryUntil.Result.NOT_TRIGGERED:
114+
self.get_logger().info("Trajectory executed without tool contact trigger")
115+
else:
116+
self.get_logger().info("Trajectory executed with tool contact trigger")
117+
118+
self.get_logger().info("Trajectory executed successfully with tool contact condition")
119+
120+
121+
if __name__ == "__main__":
122+
rclpy.init()
123+
124+
node = MoveUntilExample()
125+
try:
126+
node.process()
127+
except KeyboardInterrupt:
128+
node.get_logger().info("Interrupted")
129+
node.cancel_goal()
130+
time.sleep(2)
131+
132+
rclpy.shutdown()
Lines changed: 137 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,137 @@
1+
// Copyright 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+
//----------------------------------------------------------------------
30+
/*!\file
31+
*
32+
* \author Jacob Larsen [email protected]
33+
* \date 2025-01-17
34+
*
35+
*
36+
*
37+
*
38+
*/
39+
//----------------------------------------------------------------------
40+
41+
#ifndef UR_ROBOT_DRIVER__TRAJECTORY_UNTIL_NODE_HPP_
42+
#define UR_ROBOT_DRIVER__TRAJECTORY_UNTIL_NODE_HPP_
43+
44+
#include <memory>
45+
#include <variant>
46+
47+
#include <rclcpp/rclcpp.hpp>
48+
#include <std_msgs/msg/bool.hpp>
49+
#include <rclcpp_action/server.hpp>
50+
#include <rclcpp_action/rclcpp_action.hpp>
51+
#include <rclcpp_action/create_server.hpp>
52+
#include <rclcpp_action/server_goal_handle.hpp>
53+
#include <rclcpp/duration.hpp>
54+
#include <ur_msgs/action/tool_contact.hpp>
55+
#include <ur_msgs/action/follow_joint_trajectory_until.hpp>
56+
#include <control_msgs/action/follow_joint_trajectory.hpp>
57+
58+
namespace ur_robot_driver
59+
{
60+
class TrajectoryUntilNode : public rclcpp::Node
61+
{
62+
public:
63+
explicit TrajectoryUntilNode(const rclcpp::NodeOptions& options = rclcpp::NodeOptions());
64+
~TrajectoryUntilNode();
65+
66+
private:
67+
using TrajectoryUntilAction = ur_msgs::action::FollowJointTrajectoryUntil;
68+
69+
rclcpp_action::Server<TrajectoryUntilAction>::SharedPtr action_server_;
70+
rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SharedPtr trajectory_action_client_;
71+
72+
// Add new until types here, when available
73+
using TCClient = rclcpp_action::Client<ur_msgs::action::ToolContact>::SharedPtr;
74+
std::variant<TCClient> until_action_client_variant;
75+
76+
rclcpp::CallbackGroup::SharedPtr server_callback_group;
77+
rclcpp::CallbackGroup::SharedPtr clients_callback_group;
78+
79+
std::shared_ptr<rclcpp_action::ServerGoalHandle<TrajectoryUntilAction>> server_goal_handle_;
80+
81+
template <class ActionType, class ClientType>
82+
void send_until_goal(std::shared_ptr<const TrajectoryUntilAction::Goal> goal);
83+
84+
template <class T>
85+
void until_response_callback(const typename rclcpp_action::ClientGoalHandle<T>::SharedPtr& goal_handle);
86+
87+
template <class T>
88+
void until_result_callback(const typename rclcpp_action::ClientGoalHandle<T>::WrappedResult& result);
89+
90+
void cancel_until_goal();
91+
92+
void trajectory_response_callback(
93+
const rclcpp_action::ClientGoalHandle<control_msgs::action::FollowJointTrajectory>::SharedPtr& goal_handle);
94+
void trajectory_feedback_callback(
95+
const rclcpp_action::ClientGoalHandle<control_msgs::action::FollowJointTrajectory>::SharedPtr& goal_handle,
96+
const std::shared_ptr<const control_msgs::action::FollowJointTrajectory::Feedback> feedback);
97+
void trajectory_result_callback(
98+
const rclcpp_action::ClientGoalHandle<control_msgs::action::FollowJointTrajectory>::WrappedResult& result);
99+
100+
bool assign_until_action_client(std::shared_ptr<const TrajectoryUntilAction::Goal> goal);
101+
102+
rclcpp_action::GoalResponse goal_received_callback(const rclcpp_action::GoalUUID& uuid,
103+
std::shared_ptr<const TrajectoryUntilAction::Goal> goal);
104+
void
105+
goal_accepted_callback(const std::shared_ptr<rclcpp_action::ServerGoalHandle<TrajectoryUntilAction>> goal_handle);
106+
rclcpp_action::CancelResponse
107+
goal_cancelled_callback(const std::shared_ptr<rclcpp_action::ServerGoalHandle<TrajectoryUntilAction>> goal_handle);
108+
109+
void send_trajectory_goal(std::shared_ptr<const TrajectoryUntilAction::Goal> goal);
110+
111+
void report_goal(rclcpp_action::ClientGoalHandle<control_msgs::action::FollowJointTrajectory>::WrappedResult result);
112+
113+
template <typename UntilResult>
114+
void report_goal(UntilResult result);
115+
116+
void reset_node();
117+
118+
rclcpp_action::ClientGoalHandle<control_msgs::action::FollowJointTrajectory>::SharedPtr
119+
current_trajectory_goal_handle_;
120+
rclcpp_action::ClientGoalHandle<ur_msgs::action::ToolContact>::SharedPtr current_until_goal_handle_;
121+
122+
std::shared_ptr<TrajectoryUntilAction::Result> prealloc_res_;
123+
124+
std::shared_ptr<TrajectoryUntilAction::Feedback> prealloc_fb_;
125+
126+
std::atomic<bool> trajectory_accepted_;
127+
std::atomic<bool> until_accepted_;
128+
129+
std::condition_variable cv_until_;
130+
std::condition_variable cv_trajectory_;
131+
std::mutex mutex_until;
132+
std::mutex mutex_trajectory;
133+
};
134+
135+
} // namespace ur_robot_driver
136+
137+
#endif // UR_ROBOT_DRIVER__TRAJECTORY_UNTIL_NODE_HPP_

ur_robot_driver/launch/ur_control.launch.py

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -158,6 +158,19 @@ def launch_setup(context):
158158
arguments=["-d", rviz_config_file],
159159
)
160160

161+
trajectory_until_node = Node(
162+
package="ur_robot_driver",
163+
executable="trajectory_until_node",
164+
name="trajectory_until_node",
165+
output="screen",
166+
remappings=[
167+
(
168+
"/motion_controller/follow_joint_trajectory",
169+
f"/{initial_joint_controller.perform(context)}/follow_joint_trajectory",
170+
),
171+
],
172+
)
173+
161174
# Spawn controllers
162175
def controller_spawner(controllers, active=True):
163176
inactive_flags = ["--inactive"] if not active else []
@@ -221,6 +234,7 @@ def controller_spawner(controllers, active=True):
221234
urscript_interface,
222235
rsp,
223236
rviz_node,
237+
trajectory_until_node,
224238
] + controller_spawners
225239

226240
return nodes_to_start

0 commit comments

Comments
 (0)