Skip to content

Commit ae1f315

Browse files
[JTC] Fix hold position mode with goal_time>0 (backport ros-controls#758)
1 parent 92538a0 commit ae1f315

File tree

5 files changed

+132
-53
lines changed

5 files changed

+132
-53
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -173,6 +173,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
173173
// reserved storage for result of the command when closed loop pid adapter is used
174174
std::vector<double> tmp_command_;
175175

176+
realtime_tools::RealtimeBuffer<bool> rt_is_holding_; ///< are we holding position?
176177
// TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
177178
bool subscriber_is_active_ = false;
178179
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
@@ -186,6 +187,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
186187
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectory>>
187188
traj_msg_external_point_ptr_;
188189

190+
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ = nullptr;
191+
189192
using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
190193
using StatePublisher = realtime_tools::RealtimePublisher<ControllerStateMsg>;
191194
using StatePublisherPtr = std::unique_ptr<StatePublisher>;
@@ -274,6 +277,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
274277
bool contains_interface_type(
275278
const std::vector<std::string> & interface_type_list, const std::string & interface_type);
276279

280+
void init_hold_position_msg();
277281
void resize_joint_trajectory_point(
278282
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
279283
void resize_joint_trajectory_point_command(

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+38-26
Original file line numberDiff line numberDiff line change
@@ -230,15 +230,17 @@ controller_interface::return_type JointTrajectoryController::update(
230230
if (
231231
(before_last_point || first_sample) &&
232232
!check_state_tolerance_per_joint(
233-
state_error_, index, default_tolerances_.state_tolerance[index], false))
233+
state_error_, index, default_tolerances_.state_tolerance[index], false) &&
234+
*(rt_is_holding_.readFromRT()) == false)
234235
{
235236
tolerance_violated_while_moving = true;
236237
}
237238
// past the final point, check that we end up inside goal tolerance
238239
if (
239240
!before_last_point &&
240241
!check_state_tolerance_per_joint(
241-
state_error_, index, default_tolerances_.goal_state_tolerance[index], false))
242+
state_error_, index, default_tolerances_.goal_state_tolerance[index], false) &&
243+
*(rt_is_holding_.readFromRT()) == false)
242244
{
243245
outside_goal_tolerance = true;
244246

@@ -831,6 +833,10 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
831833
logger, "Using '%s' interpolation method.",
832834
interpolation_methods::InterpolationMethodMap.at(interpolation_method_).c_str());
833835

836+
// prepare hold_position_msg
837+
init_hold_position_msg();
838+
839+
// create subscriber and publishers
834840
joint_command_subscriber_ =
835841
get_node()->create_subscription<trajectory_msgs::msg::JointTrajectory>(
836842
"~/joint_trajectory", rclcpp::SystemDefaultsQoS(),
@@ -1018,6 +1024,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10181024
{
10191025
add_new_trajectory_msg(set_hold_position());
10201026
}
1027+
rt_is_holding_.writeFromNonRT(true);
10211028

10221029
return CallbackReturn::SUCCESS;
10231030
}
@@ -1203,6 +1210,7 @@ void JointTrajectoryController::topic_callback(
12031210
if (subscriber_is_active_)
12041211
{
12051212
add_new_trajectory_msg(msg);
1213+
rt_is_holding_.writeFromNonRT(false);
12061214
}
12071215
};
12081216

@@ -1265,6 +1273,7 @@ void JointTrajectoryController::goal_accepted_callback(
12651273
std::make_shared<trajectory_msgs::msg::JointTrajectory>(goal_handle->get_goal()->trajectory);
12661274

12671275
add_new_trajectory_msg(traj_msg);
1276+
rt_is_holding_.writeFromNonRT(false);
12681277
}
12691278

12701279
// Update the active goal
@@ -1559,31 +1568,12 @@ std::shared_ptr<trajectory_msgs::msg::JointTrajectory>
15591568
JointTrajectoryController::set_hold_position()
15601569
{
15611570
// Command to stay at current position
1562-
trajectory_msgs::msg::JointTrajectory current_pose_msg;
1563-
current_pose_msg.header.stamp =
1564-
rclcpp::Time(0.0, 0.0, get_node()->get_clock()->get_clock_type()); // start immediately
1565-
current_pose_msg.joint_names = params_.joints;
1566-
current_pose_msg.points.push_back(state_current_);
1567-
current_pose_msg.points[0].velocities.clear();
1568-
current_pose_msg.points[0].accelerations.clear();
1569-
current_pose_msg.points[0].effort.clear();
1570-
if (has_velocity_command_interface_)
1571-
{
1572-
// ensure no velocity (PID will fix this)
1573-
current_pose_msg.points[0].velocities.resize(dof_, 0.0);
1574-
}
1575-
if (has_acceleration_command_interface_)
1576-
{
1577-
// ensure no acceleration
1578-
current_pose_msg.points[0].accelerations.resize(dof_, 0.0);
1579-
}
1580-
if (has_effort_command_interface_)
1581-
{
1582-
// ensure no explicit effort (PID will fix this)
1583-
current_pose_msg.points[0].effort.resize(dof_, 0.0);
1584-
}
1571+
hold_position_msg_ptr_->points[0].positions = state_current_.positions;
15851572

1586-
return std::make_shared<trajectory_msgs::msg::JointTrajectory>(current_pose_msg);
1573+
// set flag, otherwise tolerances will be checked with holding position too
1574+
rt_is_holding_.writeFromNonRT(true);
1575+
1576+
return hold_position_msg_ptr_;
15871577
}
15881578

15891579
bool JointTrajectoryController::contains_interface_type(
@@ -1633,6 +1623,28 @@ bool JointTrajectoryController::has_active_trajectory()
16331623
return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg();
16341624
}
16351625

1626+
void JointTrajectoryController::init_hold_position_msg()
1627+
{
1628+
hold_position_msg_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
1629+
hold_position_msg_ptr_->header.stamp =
1630+
rclcpp::Time(0.0, 0.0, get_node()->get_clock()->get_clock_type()); // start immediately
1631+
hold_position_msg_ptr_->joint_names = params_.joints;
1632+
hold_position_msg_ptr_->points.resize(1); // a trivial msg only
1633+
hold_position_msg_ptr_->points[0].velocities.clear();
1634+
hold_position_msg_ptr_->points[0].accelerations.clear();
1635+
hold_position_msg_ptr_->points[0].effort.clear();
1636+
if (has_velocity_command_interface_ || has_acceleration_command_interface_)
1637+
{
1638+
// add velocity, so that trajectory sampling returns velocity points in any case
1639+
hold_position_msg_ptr_->points[0].velocities.resize(dof_, 0.0);
1640+
}
1641+
if (has_acceleration_command_interface_)
1642+
{
1643+
// add velocity, so that trajectory sampling returns acceleration points in any case
1644+
hold_position_msg_ptr_->points[0].accelerations.resize(dof_, 0.0);
1645+
}
1646+
}
1647+
16361648
} // namespace joint_trajectory_controller
16371649

16381650
#include "pluginlib/class_list_macros.hpp"

joint_trajectory_controller/test/test_trajectory_actions.cpp

+20-4
Original file line numberDiff line numberDiff line change
@@ -68,11 +68,11 @@ class TestTrajectoryActions : public TrajectoryControllerTest
6868

6969
void SetUpExecutor(
7070
const std::vector<rclcpp::Parameter> & parameters = {},
71-
bool separate_cmd_and_state_values = false)
71+
bool separate_cmd_and_state_values = false, double kp = 0.0)
7272
{
7373
setup_executor_ = true;
7474

75-
SetUpAndActivateTrajectoryController(executor_, parameters, separate_cmd_and_state_values);
75+
SetUpAndActivateTrajectoryController(executor_, parameters, separate_cmd_and_state_values, kp);
7676

7777
SetUpActionClient();
7878

@@ -247,7 +247,15 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_single_point_sendgoa
247247
// it should be holding the last position goal
248248
// i.e., active but trivial trajectory (one point only)
249249
// note: the action goal also is a trivial trajectory
250-
expectHoldingPoint(point_positions);
250+
if (traj_controller_->has_position_command_interface())
251+
{
252+
expectHoldingPoint(point_positions);
253+
}
254+
else
255+
{
256+
// no integration to position state interface from velocity/acceleration
257+
expectHoldingPoint(INITIAL_POS_JOINTS);
258+
}
251259
}
252260

253261
TEST_P(TestTrajectoryActionsTestParameterized, test_success_multi_point_sendgoal)
@@ -294,7 +302,15 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_multi_point_sendgoal
294302

295303
// it should be holding the last position goal
296304
// i.e., active but trivial trajectory (one point only)
297-
expectHoldingPoint(points_positions.at(1));
305+
if (traj_controller_->has_position_command_interface())
306+
{
307+
expectHoldingPoint(points_positions.at(1));
308+
}
309+
else
310+
{
311+
// no integration to position state interface from velocity/acceleration
312+
expectHoldingPoint(INITIAL_POS_JOINTS);
313+
}
298314
}
299315

300316
/**

joint_trajectory_controller/test/test_trajectory_controller.cpp

+10-2
Original file line numberDiff line numberDiff line change
@@ -1673,7 +1673,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_state_tolerances_fail)
16731673
rclcpp::Parameter("constraints.joint3.trajectory", state_tol)};
16741674

16751675
rclcpp::executors::MultiThreadedExecutor executor;
1676-
SetUpAndActivateTrajectoryController(executor, params, true);
1676+
double kp = 1.0; // activate feedback control for testing velocity/effort PID
1677+
SetUpAndActivateTrajectoryController(executor, params, true, kp);
16771678

16781679
// send msg
16791680
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(100);
@@ -1705,7 +1706,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_goal_tolerances_fail)
17051706
rclcpp::Parameter("constraints.goal_time", goal_time)};
17061707

17071708
rclcpp::executors::MultiThreadedExecutor executor;
1708-
SetUpAndActivateTrajectoryController(executor, params, true);
1709+
SetUpAndActivateTrajectoryController(executor, params, true, 1.0);
17091710

17101711
// send msg
17111712
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(100);
@@ -1722,6 +1723,13 @@ TEST_P(TrajectoryControllerTestParameterized, test_goal_tolerances_fail)
17221723

17231724
// it should have aborted and be holding now
17241725
expectHoldingPoint(joint_state_pos_);
1726+
1727+
// what happens if we wait longer but it harms the tolerance again?
1728+
auto hold_position = joint_state_pos_;
1729+
joint_state_pos_.at(0) = -3.3;
1730+
updateController(rclcpp::Duration(FIRST_POINT_TIME));
1731+
// it should be still holding the old point
1732+
expectHoldingPoint(hold_position);
17251733
}
17261734

17271735
// position controllers

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

+60-21
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,12 @@ const std::vector<double> INITIAL_POS_JOINTS = {
3838
const std::vector<double> INITIAL_VEL_JOINTS = {0.0, 0.0, 0.0};
3939
const std::vector<double> INITIAL_ACC_JOINTS = {0.0, 0.0, 0.0};
4040
const std::vector<double> INITIAL_EFF_JOINTS = {0.0, 0.0, 0.0};
41+
42+
bool is_same_sign_or_zero(double val1, double val2)
43+
{
44+
return val1 * val2 > 0.0 || (val1 == 0.0 && val2 == 0.0);
45+
}
46+
4147
} // namespace
4248

4349
namespace test_trajectory_controllers
@@ -465,32 +471,65 @@ class TrajectoryControllerTest : public ::testing::Test
465471
// i.e., active but trivial trajectory (one point only)
466472
EXPECT_TRUE(traj_controller_->has_trivial_traj());
467473

468-
if (traj_controller_->has_position_command_interface())
474+
if (traj_controller_->use_closed_loop_pid_adapter() == false)
469475
{
470-
EXPECT_NEAR(point.at(0), joint_pos_[0], COMMON_THRESHOLD);
471-
EXPECT_NEAR(point.at(1), joint_pos_[1], COMMON_THRESHOLD);
472-
EXPECT_NEAR(point.at(2), joint_pos_[2], COMMON_THRESHOLD);
473-
}
476+
if (traj_controller_->has_position_command_interface())
477+
{
478+
EXPECT_NEAR(point.at(0), joint_pos_[0], COMMON_THRESHOLD);
479+
EXPECT_NEAR(point.at(1), joint_pos_[1], COMMON_THRESHOLD);
480+
EXPECT_NEAR(point.at(2), joint_pos_[2], COMMON_THRESHOLD);
481+
}
474482

475-
if (traj_controller_->has_velocity_command_interface())
476-
{
477-
EXPECT_EQ(0.0, joint_vel_[0]);
478-
EXPECT_EQ(0.0, joint_vel_[1]);
479-
EXPECT_EQ(0.0, joint_vel_[2]);
480-
}
483+
if (traj_controller_->has_velocity_command_interface())
484+
{
485+
EXPECT_EQ(0.0, joint_vel_[0]);
486+
EXPECT_EQ(0.0, joint_vel_[1]);
487+
EXPECT_EQ(0.0, joint_vel_[2]);
488+
}
481489

482-
if (traj_controller_->has_acceleration_command_interface())
483-
{
484-
EXPECT_EQ(0.0, joint_acc_[0]);
485-
EXPECT_EQ(0.0, joint_acc_[1]);
486-
EXPECT_EQ(0.0, joint_acc_[2]);
487-
}
490+
if (traj_controller_->has_acceleration_command_interface())
491+
{
492+
EXPECT_EQ(0.0, joint_acc_[0]);
493+
EXPECT_EQ(0.0, joint_acc_[1]);
494+
EXPECT_EQ(0.0, joint_acc_[2]);
495+
}
488496

489-
if (traj_controller_->has_effort_command_interface())
497+
if (traj_controller_->has_effort_command_interface())
498+
{
499+
EXPECT_EQ(0.0, joint_eff_[0]);
500+
EXPECT_EQ(0.0, joint_eff_[1]);
501+
EXPECT_EQ(0.0, joint_eff_[2]);
502+
}
503+
}
504+
else
490505
{
491-
EXPECT_EQ(0.0, joint_eff_[0]);
492-
EXPECT_EQ(0.0, joint_eff_[1]);
493-
EXPECT_EQ(0.0, joint_eff_[2]);
506+
// velocity or effort PID?
507+
// velocity setpoint is always zero -> feedforward term does not have an effect
508+
// --> set kp > 0.0 in test
509+
if (traj_controller_->has_velocity_command_interface())
510+
{
511+
EXPECT_TRUE(is_same_sign_or_zero(point.at(0) - joint_state_pos_[0], joint_vel_[0]))
512+
<< "current error: " << point.at(0) - joint_state_pos_[0] << ", velocity command is "
513+
<< joint_vel_[0];
514+
EXPECT_TRUE(is_same_sign_or_zero(point.at(1) - joint_state_pos_[1], joint_vel_[1]))
515+
<< "current error: " << point.at(1) - joint_state_pos_[1] << ", velocity command is "
516+
<< joint_vel_[1];
517+
EXPECT_TRUE(is_same_sign_or_zero(point.at(2) - joint_state_pos_[2], joint_vel_[2]))
518+
<< "current error: " << point.at(2) - joint_state_pos_[2] << ", velocity command is "
519+
<< joint_vel_[2];
520+
}
521+
if (traj_controller_->has_effort_command_interface())
522+
{
523+
EXPECT_TRUE(is_same_sign_or_zero(point.at(0) - joint_state_pos_[0], joint_eff_[0]))
524+
<< "current error: " << point.at(0) - joint_state_pos_[0] << ", effort command is "
525+
<< joint_eff_[0];
526+
EXPECT_TRUE(is_same_sign_or_zero(point.at(1) - joint_state_pos_[1], joint_eff_[1]))
527+
<< "current error: " << point.at(1) - joint_state_pos_[1] << ", effort command is "
528+
<< joint_eff_[1];
529+
EXPECT_TRUE(is_same_sign_or_zero(point.at(2) - joint_state_pos_[2], joint_eff_[2]))
530+
<< "current error: " << point.at(2) - joint_state_pos_[2] << ", effort command is "
531+
<< joint_eff_[2];
532+
}
494533
}
495534
}
496535

0 commit comments

Comments
 (0)