Skip to content

Commit 4683e53

Browse files
urmahpFelix Exner
andauthored
Implemented spline interpolation in joint space (#543)
* Added service to activate or deactivate spline interpolation * Added velocities to test move function in order to force cubic spline interpolation * Default to using spline interpolation when doing trajectory forwarding. I think this approach is superior to hardcoding a blend radius with MoveJ commands. This way we will result in a path that is closer to the one planned by MoveIt! * Position only spline interpolation got explicitly removed. --------- Co-authored-by: Felix Exner <[email protected]>
1 parent d7af634 commit 4683e53

File tree

5 files changed

+77
-1
lines changed

5 files changed

+77
-1
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@
3838
#include <std_msgs/Float64.h>
3939
#include <std_msgs/String.h>
4040
#include <std_srvs/Trigger.h>
41+
#include <std_srvs/SetBool.h>
4142
#include <realtime_tools/realtime_publisher.h>
4243
#include <tf2_msgs/TFMessage.h>
4344
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
@@ -213,6 +214,7 @@ class HardwareInterface : public hardware_interface::RobotHW
213214
bool zeroFTSensor(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
214215
void commandCallback(const std_msgs::StringConstPtr& msg);
215216
bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& res);
217+
bool activateSplineInterpolation(std_srvs::SetBoolRequest& req, std_srvs::SetBoolResponse& res);
216218

217219
std::unique_ptr<urcl::UrDriver> ur_driver_;
218220
std::unique_ptr<DashboardClientROS> dashboard_client_;
@@ -236,6 +238,7 @@ class HardwareInterface : public hardware_interface::RobotHW
236238
ros::ServiceServer deactivate_srv_;
237239
ros::ServiceServer tare_sensor_srv_;
238240
ros::ServiceServer set_payload_srv_;
241+
ros::ServiceServer activate_spline_interpolation_srv_;
239242

240243
hardware_interface::JointStateInterface js_interface_;
241244
scaled_controllers::ScaledPositionJointInterface spj_interface_;
@@ -325,6 +328,7 @@ class HardwareInterface : public hardware_interface::RobotHW
325328
std::atomic<bool> cartesian_forward_controller_running_;
326329
std::atomic<bool> twist_controller_running_;
327330
std::atomic<bool> pose_controller_running_;
331+
std::atomic<bool> use_spline_interpolation_;
328332

329333
PausingState pausing_state_;
330334
double pausing_ramp_up_increment_;

ur_robot_driver/launch/ur_common.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
<arg name="robot_description_file" doc="Robot description launch file."/>
2525
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
2626
<arg name="ur_hardware_interface_node_required" default="true" doc="Shut down ros environment if ur_hardware_interface-node dies."/>
27+
<arg name="use_spline_interpolation" default="true" doc="True if splines should be used as interpolation on the robot controller when forwarding trajectory, if false movej or movel commands are used"/>
2728

2829
<!-- robot model -->
2930
<include file="$(arg robot_description_file)">
@@ -57,5 +58,6 @@
5758
<arg name="tool_device_name" value="$(arg tool_device_name)"/>
5859
<arg name="tool_tcp_port" value="$(arg tool_tcp_port)"/>
5960
<arg name="ur_hardware_interface_node_required" value="$(arg ur_hardware_interface_node_required)"/>
61+
<arg name="use_spline_interpolation" value="$(arg use_spline_interpolation)"/>
6062
</include>
6163
</launch>

ur_robot_driver/launch/ur_control.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
<arg name="servoj_gain" default="2000" doc="Specify gain for servoing to position in joint space. A higher gain can sharpen the trajectory."/>
3434
<arg name="servoj_lookahead_time" default="0.03" doc="Specify lookahead time for servoing to position in joint space. A longer lookahead time can smooth the trajectory."/>
3535
<arg name="ur_hardware_interface_node_required" default="true" doc="Shut down ros environment if ur_hardware_interface-node dies."/>
36+
<arg name="use_spline_interpolation" default="true" doc="True if splines should be used as interpolation on the robot controller when forwarding trajectory, if false movej or movel commands are used"/>
3637

3738
<!-- Load hardware interface -->
3839
<node name="ur_hardware_interface" pkg="ur_robot_driver" type="ur_robot_driver_node" output="screen" launch-prefix="$(arg launch_prefix)" required="$(arg ur_hardware_interface_node_required)">
@@ -58,6 +59,7 @@
5859
<param name="tool_tx_idle_chars" value="$(arg tool_tx_idle_chars)"/>
5960
<param name="servoj_gain" value="$(arg servoj_gain)"/>
6061
<param name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)"/>
62+
<param name="use_spline_interpolation" value="$(arg use_spline_interpolation)"/>
6163
</node>
6264

6365
<!-- Starts socat to bridge the robot's tool communication interface to a local tty device -->

ur_robot_driver/scripts/test_move

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -124,10 +124,15 @@ class TrajectoryClient:
124124
position_list = [[0, -1.57, -1.57, 0, 0, 0]]
125125
position_list.append([0.2, -1.57, -1.57, 0, 0, 0])
126126
position_list.append([-0.5, -1.57, -1.2, 0, 0, 0])
127+
128+
velocity_list = [[0.2, 0, 0, 0, 0, 0]]
129+
velocity_list.append([-0.2, 0, 0, 0, 0, 0])
130+
velocity_list.append([0, 0, 0, 0, 0, 0])
127131
duration_list = [3.0, 7.0, 10.0]
128132
for i, position in enumerate(position_list):
129133
point = JointTrajectoryPoint()
130134
point.positions = position
135+
point.velocities = velocity_list[i]
131136
point.time_from_start = rospy.Duration(duration_list[i])
132137
goal.trajectory.points.append(point)
133138

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 64 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -176,6 +176,10 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
176176
return false;
177177
}
178178

179+
// True if splines should be used as interpolation on the robot controller when forwarding trajectory, if false movej
180+
// or movel commands are used
181+
use_spline_interpolation_ = robot_hw_nh.param<bool>("use_spline_interpolation", "true");
182+
179183
// Whenever the runtime state of the "External Control" program node in the UR-program changes, a
180184
// message gets published here. So this is equivalent to the information whether the robot accepts
181185
// commands from ROS side.
@@ -451,6 +455,11 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
451455
// Setup the mounted payload through a ROS service
452456
set_payload_srv_ = robot_hw_nh.advertiseService("set_payload", &HardwareInterface::setPayload, this);
453457

458+
// Call this to activate or deactivate using spline interpolation locally on the UR controller, when forwarding
459+
// trajectories to the UR robot.
460+
activate_spline_interpolation_srv_ = robot_hw_nh.advertiseService(
461+
"activate_spline_interpolation", &HardwareInterface::activateSplineInterpolation, this);
462+
454463
ur_driver_->startRTDECommunication();
455464
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");
456465

@@ -1190,6 +1199,21 @@ void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg)
11901199
}
11911200
}
11921201

1202+
bool HardwareInterface::activateSplineInterpolation(std_srvs::SetBoolRequest& req, std_srvs::SetBoolResponse& res)
1203+
{
1204+
use_spline_interpolation_ = req.data;
1205+
if (use_spline_interpolation_)
1206+
{
1207+
res.message = "Activated spline interpolation in forward trajectory mode.";
1208+
}
1209+
else
1210+
{
1211+
res.message = "Deactivated spline interpolation in forward trajectory mode.";
1212+
}
1213+
res.success = true;
1214+
return true;
1215+
}
1216+
11931217
void HardwareInterface::publishRobotAndSafetyMode()
11941218
{
11951219
if (robot_mode_pub_)
@@ -1255,7 +1279,46 @@ void HardwareInterface::startJointInterpolation(const hardware_interface::JointT
12551279
p[4] = point.positions[4];
12561280
p[5] = point.positions[5];
12571281
double next_time = point.time_from_start.toSec();
1258-
ur_driver_->writeTrajectoryPoint(p, false, next_time - last_time);
1282+
if (!use_spline_interpolation_)
1283+
{
1284+
ur_driver_->writeTrajectoryPoint(p, false, next_time - last_time);
1285+
}
1286+
else // Use spline interpolation
1287+
{
1288+
if (point.velocities.size() == 6 && point.accelerations.size() == 6)
1289+
{
1290+
urcl::vector6d_t v, a;
1291+
v[0] = point.velocities[0];
1292+
v[1] = point.velocities[1];
1293+
v[2] = point.velocities[2];
1294+
v[3] = point.velocities[3];
1295+
v[4] = point.velocities[4];
1296+
v[5] = point.velocities[5];
1297+
1298+
a[0] = point.accelerations[0];
1299+
a[1] = point.accelerations[1];
1300+
a[2] = point.accelerations[2];
1301+
a[3] = point.accelerations[3];
1302+
a[4] = point.accelerations[4];
1303+
a[5] = point.accelerations[5];
1304+
ur_driver_->writeTrajectorySplinePoint(p, v, a, next_time - last_time);
1305+
}
1306+
else if (point.velocities.size() == 6)
1307+
{
1308+
urcl::vector6d_t v;
1309+
v[0] = point.velocities[0];
1310+
v[1] = point.velocities[1];
1311+
v[2] = point.velocities[2];
1312+
v[3] = point.velocities[3];
1313+
v[4] = point.velocities[4];
1314+
v[5] = point.velocities[5];
1315+
ur_driver_->writeTrajectorySplinePoint(p, v, next_time - last_time);
1316+
}
1317+
else
1318+
{
1319+
ROS_ERROR_THROTTLE(1, "Spline interpolation using positions only is not supported.");
1320+
}
1321+
}
12591322
last_time = next_time;
12601323
}
12611324
ROS_DEBUG("Finished Sending Trajectory");

0 commit comments

Comments
 (0)