Skip to content

Commit c728db8

Browse files
mergify[bot]fmauchchristophfroehlich
authored
[JTC] Make goal_time_tolerance overwrite default value only if explicitly set (backport #1192 + #1209) (#1207)
--------- Co-authored-by: Felix Exner (fexner) <[email protected]> Co-authored-by: Christoph Froehlich <[email protected]>
1 parent f533cfd commit c728db8

File tree

4 files changed

+107
-131
lines changed

4 files changed

+107
-131
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/tolerances.hpp

Lines changed: 72 additions & 114 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
#define JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
3232

3333
#include <limits>
34+
#include <stdexcept>
3435
#include <string>
3536
#include <vector>
3637

@@ -126,6 +127,33 @@ SegmentTolerances get_segment_tolerances(rclcpp::Logger & jtc_logger, const Para
126127
return tolerances;
127128
}
128129

130+
double resolve_tolerance_source(const double default_value, const double goal_value)
131+
{
132+
// from
133+
// https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/JointTolerance.msg
134+
// There are two special values for tolerances:
135+
// * 0 - The tolerance is unspecified and will remain at whatever the default is
136+
// * -1 - The tolerance is "erased".
137+
// If there was a default, the joint will be allowed to move without restriction.
138+
constexpr double ERASE_VALUE = -1.0;
139+
auto is_erase_value = [](double value)
140+
{ return fabs(value - ERASE_VALUE) < std::numeric_limits<float>::epsilon(); };
141+
142+
if (goal_value > 0.0)
143+
{
144+
return goal_value;
145+
}
146+
else if (is_erase_value(goal_value))
147+
{
148+
return 0.0;
149+
}
150+
else if (goal_value < 0.0)
151+
{
152+
throw std::runtime_error("Illegal tolerance value.");
153+
}
154+
return default_value;
155+
}
156+
129157
/**
130158
* \brief Populate trajectory segment tolerances using data from an action goal.
131159
*
@@ -141,20 +169,22 @@ SegmentTolerances get_segment_tolerances(
141169
const std::vector<std::string> & joints)
142170
{
143171
SegmentTolerances active_tolerances(default_tolerances);
144-
145-
active_tolerances.goal_time_tolerance = rclcpp::Duration(goal.goal_time_tolerance).seconds();
146172
static auto logger = jtc_logger.get_child("tolerance");
147-
RCLCPP_DEBUG(logger, "%s %f", "goal_time", active_tolerances.goal_time_tolerance);
148173

149-
// from
150-
// https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/JointTolerance.msg
151-
// There are two special values for tolerances:
152-
// * 0 - The tolerance is unspecified and will remain at whatever the default is
153-
// * -1 - The tolerance is "erased".
154-
// If there was a default, the joint will be allowed to move without restriction.
155-
constexpr double ERASE_VALUE = -1.0;
156-
auto is_erase_value = [](double value)
157-
{ return fabs(value - ERASE_VALUE) < std::numeric_limits<float>::epsilon(); };
174+
try
175+
{
176+
active_tolerances.goal_time_tolerance = resolve_tolerance_source(
177+
default_tolerances.goal_time_tolerance, rclcpp::Duration(goal.goal_time_tolerance).seconds());
178+
}
179+
catch (const std::runtime_error & e)
180+
{
181+
RCLCPP_ERROR_STREAM(
182+
logger, "Specified illegal goal_time_tolerance: "
183+
<< rclcpp::Duration(goal.goal_time_tolerance).seconds()
184+
<< ". Using default tolerances");
185+
return default_tolerances;
186+
}
187+
RCLCPP_DEBUG(logger, "%s %f", "goal_time", active_tolerances.goal_time_tolerance);
158188

159189
// State and goal state tolerances
160190
for (auto joint_tol : goal.path_tolerance)
@@ -173,60 +203,24 @@ SegmentTolerances get_segment_tolerances(
173203
return default_tolerances;
174204
}
175205
auto i = std::distance(joints.cbegin(), it);
176-
if (joint_tol.position > 0.0)
177-
{
178-
active_tolerances.state_tolerance[i].position = joint_tol.position;
179-
}
180-
else if (is_erase_value(joint_tol.position))
206+
std::string interface = "";
207+
try
181208
{
182-
active_tolerances.state_tolerance[i].position = 0.0;
209+
interface = "position";
210+
active_tolerances.state_tolerance[i].position = resolve_tolerance_source(
211+
default_tolerances.state_tolerance[i].position, joint_tol.position);
212+
interface = "velocity";
213+
active_tolerances.state_tolerance[i].velocity = resolve_tolerance_source(
214+
default_tolerances.state_tolerance[i].velocity, joint_tol.velocity);
215+
interface = "acceleration";
216+
active_tolerances.state_tolerance[i].acceleration = resolve_tolerance_source(
217+
default_tolerances.state_tolerance[i].acceleration, joint_tol.acceleration);
183218
}
184-
else if (joint_tol.position < 0.0)
219+
catch (const std::runtime_error & e)
185220
{
186-
RCLCPP_ERROR(
187-
logger, "%s",
188-
("joint '" + joint +
189-
"' specified in goal.path_tolerance has a invalid position tolerance. "
190-
"Using default tolerances.")
191-
.c_str());
192-
return default_tolerances;
193-
}
194-
195-
if (joint_tol.velocity > 0.0)
196-
{
197-
active_tolerances.state_tolerance[i].velocity = joint_tol.velocity;
198-
}
199-
else if (is_erase_value(joint_tol.velocity))
200-
{
201-
active_tolerances.state_tolerance[i].velocity = 0.0;
202-
}
203-
else if (joint_tol.velocity < 0.0)
204-
{
205-
RCLCPP_ERROR(
206-
logger, "%s",
207-
("joint '" + joint +
208-
"' specified in goal.path_tolerance has a invalid velocity tolerance. "
209-
"Using default tolerances.")
210-
.c_str());
211-
return default_tolerances;
212-
}
213-
214-
if (joint_tol.acceleration > 0.0)
215-
{
216-
active_tolerances.state_tolerance[i].acceleration = joint_tol.acceleration;
217-
}
218-
else if (is_erase_value(joint_tol.acceleration))
219-
{
220-
active_tolerances.state_tolerance[i].acceleration = 0.0;
221-
}
222-
else if (joint_tol.acceleration < 0.0)
223-
{
224-
RCLCPP_ERROR(
225-
logger, "%s",
226-
("joint '" + joint +
227-
"' specified in goal.path_tolerance has a invalid acceleration tolerance. "
228-
"Using default tolerances.")
229-
.c_str());
221+
RCLCPP_ERROR_STREAM(
222+
logger, "joint '" << joint << "' specified in goal.path_tolerance has a invalid "
223+
<< interface << " tolerance. Using default tolerances.");
230224
return default_tolerances;
231225
}
232226

@@ -256,60 +250,24 @@ SegmentTolerances get_segment_tolerances(
256250
return default_tolerances;
257251
}
258252
auto i = std::distance(joints.cbegin(), it);
259-
if (goal_tol.position > 0.0)
260-
{
261-
active_tolerances.goal_state_tolerance[i].position = goal_tol.position;
262-
}
263-
else if (is_erase_value(goal_tol.position))
264-
{
265-
active_tolerances.goal_state_tolerance[i].position = 0.0;
266-
}
267-
else if (goal_tol.position < 0.0)
268-
{
269-
RCLCPP_ERROR(
270-
logger, "%s",
271-
("joint '" + joint +
272-
"' specified in goal.goal_tolerance has a invalid position tolerance. "
273-
"Using default tolerances.")
274-
.c_str());
275-
return default_tolerances;
276-
}
277-
278-
if (goal_tol.velocity > 0.0)
279-
{
280-
active_tolerances.goal_state_tolerance[i].velocity = goal_tol.velocity;
281-
}
282-
else if (is_erase_value(goal_tol.velocity))
253+
std::string interface = "";
254+
try
283255
{
284-
active_tolerances.goal_state_tolerance[i].velocity = 0.0;
256+
interface = "position";
257+
active_tolerances.goal_state_tolerance[i].position = resolve_tolerance_source(
258+
default_tolerances.goal_state_tolerance[i].position, goal_tol.position);
259+
interface = "velocity";
260+
active_tolerances.goal_state_tolerance[i].velocity = resolve_tolerance_source(
261+
default_tolerances.goal_state_tolerance[i].velocity, goal_tol.velocity);
262+
interface = "acceleration";
263+
active_tolerances.goal_state_tolerance[i].acceleration = resolve_tolerance_source(
264+
default_tolerances.goal_state_tolerance[i].acceleration, goal_tol.acceleration);
285265
}
286-
else if (goal_tol.velocity < 0.0)
266+
catch (const std::runtime_error & e)
287267
{
288-
RCLCPP_ERROR(
289-
logger, "%s",
290-
("joint '" + joint +
291-
"' specified in goal.goal_tolerance has a invalid velocity tolerance. "
292-
"Using default tolerances.")
293-
.c_str());
294-
return default_tolerances;
295-
}
296-
297-
if (goal_tol.acceleration > 0.0)
298-
{
299-
active_tolerances.goal_state_tolerance[i].acceleration = goal_tol.acceleration;
300-
}
301-
else if (is_erase_value(goal_tol.acceleration))
302-
{
303-
active_tolerances.goal_state_tolerance[i].acceleration = 0.0;
304-
}
305-
else if (goal_tol.acceleration < 0.0)
306-
{
307-
RCLCPP_ERROR(
308-
logger, "%s",
309-
("joint '" + joint +
310-
"' specified in goal.goal_tolerance has a invalid acceleration tolerance. "
311-
"Using default tolerances.")
312-
.c_str());
268+
RCLCPP_ERROR_STREAM(
269+
logger, "joint '" << joint << "' specified in goal.goal_tolerance has a invalid "
270+
<< interface << " tolerance. Using default tolerances.");
313271
return default_tolerances;
314272
}
315273

joint_trajectory_controller/test/test_tolerances.cpp

Lines changed: 28 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -32,14 +32,14 @@ using trajectory_msgs::msg::JointTrajectoryPoint;
3232
std::vector<std::string> joint_names_ = {"joint1", "joint2", "joint3"};
3333

3434
control_msgs::action::FollowJointTrajectory_Goal prepareGoalMsg(
35-
const std::vector<JointTrajectoryPoint> & points, double timeout,
35+
const std::vector<JointTrajectoryPoint> & points, double goal_time_tolerance,
3636
const std::vector<control_msgs::msg::JointTolerance> path_tolerance =
3737
std::vector<control_msgs::msg::JointTolerance>(),
3838
const std::vector<control_msgs::msg::JointTolerance> goal_tolerance =
3939
std::vector<control_msgs::msg::JointTolerance>())
4040
{
4141
control_msgs::action::FollowJointTrajectory_Goal goal_msg;
42-
goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds(timeout);
42+
goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds(goal_time_tolerance);
4343
goal_msg.goal_tolerance = goal_tolerance;
4444
goal_msg.path_tolerance = path_tolerance;
4545
goal_msg.trajectory.joint_names = joint_names_;
@@ -183,7 +183,7 @@ TEST_F(TestTolerancesFixture, test_deactivate_tolerances)
183183
path_tolerance.push_back(tolerance);
184184
goal_tolerance.push_back(tolerance);
185185

186-
auto goal_msg = prepareGoalMsg(points, 0.0, path_tolerance, goal_tolerance);
186+
auto goal_msg = prepareGoalMsg(points, -1.0, path_tolerance, goal_tolerance);
187187
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
188188
logger, default_tolerances, goal_msg, params.joints);
189189

@@ -215,6 +215,31 @@ TEST_F(TestTolerancesFixture, test_deactivate_tolerances)
215215
// send goal with invalid tolerances, are the default ones used?
216216
TEST_F(TestTolerancesFixture, test_invalid_tolerances)
217217
{
218+
{
219+
SCOPED_TRACE("negative goal_time_tolerance");
220+
std::vector<JointTrajectoryPoint> points;
221+
JointTrajectoryPoint point;
222+
point.time_from_start = rclcpp::Duration::from_seconds(0.5);
223+
point.positions.resize(joint_names_.size());
224+
225+
point.positions[0] = 1.0;
226+
point.positions[1] = 2.0;
227+
point.positions[2] = 3.0;
228+
points.push_back(point);
229+
230+
std::vector<control_msgs::msg::JointTolerance> path_tolerance;
231+
control_msgs::msg::JointTolerance tolerance;
232+
tolerance.name = "joint1";
233+
tolerance.position = 0.0;
234+
tolerance.velocity = 0.0;
235+
tolerance.acceleration = 0.0;
236+
path_tolerance.push_back(tolerance);
237+
238+
auto goal_msg = prepareGoalMsg(points, -123.0, path_tolerance);
239+
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
240+
logger, default_tolerances, goal_msg, params.joints);
241+
expectDefaultTolerances(active_tolerances);
242+
}
218243
{
219244
SCOPED_TRACE("negative path position tolerance");
220245
std::vector<JointTrajectoryPoint> points;
@@ -238,7 +263,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
238263
auto goal_msg = prepareGoalMsg(points, 3.0, path_tolerance);
239264
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
240265
logger, default_tolerances, goal_msg, params.joints);
241-
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
242266
expectDefaultTolerances(active_tolerances);
243267
}
244268
{
@@ -264,7 +288,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
264288
auto goal_msg = prepareGoalMsg(points, 3.0, path_tolerance);
265289
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
266290
logger, default_tolerances, goal_msg, params.joints);
267-
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
268291
expectDefaultTolerances(active_tolerances);
269292
}
270293
{
@@ -290,7 +313,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
290313
auto goal_msg = prepareGoalMsg(points, 3.0, path_tolerance);
291314
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
292315
logger, default_tolerances, goal_msg, params.joints);
293-
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
294316
expectDefaultTolerances(active_tolerances);
295317
}
296318
{
@@ -317,7 +339,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
317339
prepareGoalMsg(points, 3.0, std::vector<control_msgs::msg::JointTolerance>(), goal_tolerance);
318340
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
319341
logger, default_tolerances, goal_msg, params.joints);
320-
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
321342
expectDefaultTolerances(active_tolerances);
322343
}
323344
{
@@ -344,7 +365,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
344365
prepareGoalMsg(points, 3.0, std::vector<control_msgs::msg::JointTolerance>(), goal_tolerance);
345366
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
346367
logger, default_tolerances, goal_msg, params.joints);
347-
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
348368
expectDefaultTolerances(active_tolerances);
349369
}
350370
{
@@ -371,7 +391,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
371391
prepareGoalMsg(points, 3.0, std::vector<control_msgs::msg::JointTolerance>(), goal_tolerance);
372392
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
373393
logger, default_tolerances, goal_msg, params.joints);
374-
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
375394
expectDefaultTolerances(active_tolerances);
376395
}
377396
}
@@ -395,7 +414,6 @@ TEST_F(TestTolerancesFixture, test_invalid_joints_path_tolerance)
395414
auto goal_msg = prepareGoalMsg(points, 3.0, path_tolerance);
396415
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
397416
logger, default_tolerances, goal_msg, params.joints);
398-
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
399417
expectDefaultTolerances(active_tolerances);
400418
}
401419
TEST_F(TestTolerancesFixture, test_invalid_joints_goal_tolerance)
@@ -419,6 +437,5 @@ TEST_F(TestTolerancesFixture, test_invalid_joints_goal_tolerance)
419437
prepareGoalMsg(points, 3.0, std::vector<control_msgs::msg::JointTolerance>(), goal_tolerance);
420438
auto active_tolerances = joint_trajectory_controller::get_segment_tolerances(
421439
logger, default_tolerances, goal_msg, params.joints);
422-
EXPECT_DOUBLE_EQ(active_tolerances.goal_time_tolerance, default_goal_time);
423440
expectDefaultTolerances(active_tolerances);
424441
}

0 commit comments

Comments
 (0)