Skip to content

Commit 9322bcb

Browse files
Add RT buffer to base class
1 parent 005d1b1 commit 9322bcb

File tree

5 files changed

+127
-49
lines changed

5 files changed

+127
-49
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 26 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -179,11 +179,13 @@ controller_interface::return_type JointTrajectoryController::update(
179179
// Check if a new external message has been received from nonRT threads
180180
auto current_external_msg = traj_external_point_ptr_->get_trajectory_msg();
181181
auto new_external_msg = traj_msg_external_point_ptr_.readFromRT();
182-
// Discard, if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
183-
// TODO(christophfroehlich) wait until gains were computed by the trajectory controller
182+
// Discard,
183+
// if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
184+
// and if use_closed_loop_control_law_: wait until control law is computed by the traj_contr_
184185
if (
185186
current_external_msg != *new_external_msg &&
186-
(*(rt_has_pending_goal_.readFromRT()) && !active_goal) == false)
187+
(*(rt_has_pending_goal_.readFromRT()) && !active_goal) == false &&
188+
(use_closed_loop_control_law_ == false || traj_contr_->is_valid()))
187189
{
188190
fill_partial_goal(*new_external_msg);
189191
sort_to_local_joint_order(*new_external_msg);
@@ -781,7 +783,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
781783
params_.controller_plugin.c_str(), ex.what());
782784
return CallbackReturn::FAILURE;
783785
}
784-
if (traj_contr_->initialize(get_node(), command_joint_names_) == false)
786+
if (traj_contr_->initialize(get_node()) == false)
785787
{
786788
RCLCPP_FATAL(
787789
logger,
@@ -791,9 +793,20 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
791793
}
792794
else
793795
{
794-
RCLCPP_INFO(
795-
logger, "The trajectory controller plugin `%s` was loaded.",
796-
params_.controller_plugin.c_str());
796+
if (traj_contr_->configure() == false)
797+
{
798+
RCLCPP_FATAL(
799+
logger,
800+
"The trajectory controller plugin `%s` failed to initialize for some reason. Aborting.",
801+
params_.controller_plugin.c_str());
802+
return CallbackReturn::FAILURE;
803+
}
804+
else
805+
{
806+
RCLCPP_INFO(
807+
logger, "The trajectory controller plugin `%s` was loaded and configured.",
808+
params_.controller_plugin.c_str());
809+
}
797810
}
798811

799812
tmp_command_.resize(dof_, 0.0);
@@ -1059,6 +1072,11 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10591072
last_commanded_state_ = state;
10601073
}
10611074

1075+
if (use_closed_loop_control_law_)
1076+
{
1077+
traj_contr_->activate();
1078+
}
1079+
10621080
// Should the controller start by holding position at the beginning of active state?
10631081
if (params_.start_with_holding)
10641082
{
@@ -1548,7 +1566,7 @@ void JointTrajectoryController::add_new_trajectory_msg(
15481566
// compute gains of controller
15491567
if (use_closed_loop_control_law_)
15501568
{
1551-
if (traj_contr_->computeGainsNonRT(traj_msg) == false)
1569+
if (traj_contr_->computeControlLawNonRT(traj_msg) == false)
15521570
{
15531571
RCLCPP_ERROR(get_node()->get_logger(), "Failed to compute gains for trajectory.");
15541572
}

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/pid_trajectory_plugin.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -33,11 +33,13 @@ namespace joint_trajectory_controller_plugins
3333
class PidTrajectoryPlugin : public TrajectoryControllerBase
3434
{
3535
public:
36-
bool initialize(
37-
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
38-
std::vector<std::string> command_joint_names) override;
36+
bool initialize(rclcpp_lifecycle::LifecycleNode::SharedPtr node) override;
3937

40-
bool computeGainsNonRT(
38+
bool configure() override;
39+
40+
bool activate() override;
41+
42+
bool computeControlLaw(
4143
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & /*trajectory*/) override;
4244

4345
bool updateGainsRT() override;
@@ -58,8 +60,6 @@ class PidTrajectoryPlugin : public TrajectoryControllerBase
5860

5961
// number of command joints
6062
size_t num_cmd_joints_;
61-
// name of the command joints
62-
std::vector<std::string> command_joint_names_;
6363
// PID controllers
6464
std::vector<PidPtr> pids_;
6565
// Feed-forward velocity weight factor when calculating closed loop pid adapter's command

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/trajectory_controller_base.hpp

Lines changed: 51 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include "rclcpp/rclcpp.hpp"
2323
#include "rclcpp/time.hpp"
2424
#include "rclcpp_lifecycle/lifecycle_node.hpp"
25+
#include "realtime_tools/realtime_buffer.h"
2526
#include "trajectory_msgs/msg/joint_trajectory.hpp"
2627
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
2728

@@ -40,26 +41,50 @@ class TrajectoryControllerBase
4041

4142
/**
4243
* @brief initialize the controller plugin.
43-
* parse read-only parameters and do pre-allocate memory for the controller
44+
* declare parameters
4445
*/
4546
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
46-
virtual bool initialize(
47-
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
48-
std::vector<std::string> command_joint_names) = 0;
47+
virtual bool initialize(rclcpp_lifecycle::LifecycleNode::SharedPtr node) = 0;
4948

5049
/**
51-
* @brief compute the gains from the given trajectory from a non-RT thread
50+
* @brief configure the controller plugin.
51+
* parse read-only parameters, pre-allocate memory for the controller
52+
*/
53+
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
54+
virtual bool configure() = 0;
55+
56+
/**
57+
* @brief activate the controller plugin.
58+
* parse parameters
59+
*/
60+
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
61+
virtual bool activate() = 0;
62+
63+
/**
64+
* @brief compute the control law for the given trajectory
65+
*
66+
* this method can take more time to compute the control law. Hence, it will block the execution
67+
* of the trajectory until it finishes
68+
*
69+
* this method is not virtual, any overrides won't be called by JTC. Instead, override
70+
* computeControlLaw for your implementation
71+
*
5272
* @return true if the gains were computed, false otherwise
5373
*/
5474
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
55-
virtual bool computeGainsNonRT(
56-
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & trajectory) = 0;
75+
bool computeControlLawNonRT(
76+
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & trajectory)
77+
{
78+
rt_controller_valid_.writeFromNonRT(false);
79+
auto ret = computeControlLaw(trajectory);
80+
rt_controller_valid_.writeFromNonRT(true);
81+
return ret;
82+
}
5783

5884
/**
59-
* @brief update the gains from the given trajectory from a RT thread
85+
* @brief update the gains from a RT thread
6086
*
61-
* this method must finish quickly (within one controller-update rate,
62-
* and should not allocate memory
87+
* this method must finish quickly (within one controller-update rate)
6388
*
6489
* @return true if the gains were updated, false otherwise
6590
*/
@@ -82,9 +107,25 @@ class TrajectoryControllerBase
82107
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
83108
virtual void reset() = 0;
84109

110+
/**
111+
* @return true if the control law is valid (updated with the trajectory)
112+
*/
113+
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
114+
bool is_valid() { return rt_controller_valid_.readFromRT(); }
115+
85116
protected:
86117
// the node handle for parameter handling
87118
rclcpp_lifecycle::LifecycleNode::SharedPtr node_;
119+
// Are we computing the control law or is it valid?
120+
realtime_tools::RealtimeBuffer<bool> rt_controller_valid_;
121+
122+
/**
123+
* @brief compute the control law from the given trajectory
124+
* @return true if the gains were computed, false otherwise
125+
*/
126+
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
127+
virtual bool computeControlLaw(
128+
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & trajectory) = 0;
88129
};
89130

90131
} // namespace joint_trajectory_controller_plugins

joint_trajectory_controller_plugins/src/pid_trajectory_plugin.cpp

Lines changed: 30 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -17,26 +17,38 @@
1717
namespace joint_trajectory_controller_plugins
1818
{
1919

20-
bool PidTrajectoryPlugin::initialize(
21-
rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::vector<std::string> command_joint_names)
20+
bool PidTrajectoryPlugin::initialize(rclcpp_lifecycle::LifecycleNode::SharedPtr node)
2221
{
2322
node_ = node;
24-
command_joint_names_ = command_joint_names;
2523

2624
try
2725
{
2826
// Create the parameter listener and get the parameters
2927
param_listener_ = std::make_shared<ParamListener>(node_);
30-
params_ = param_listener_->get_params();
3128
}
3229
catch (const std::exception & e)
3330
{
3431
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
3532
return false;
3633
}
3734

35+
return true;
36+
}
37+
38+
bool PidTrajectoryPlugin::configure()
39+
{
40+
try
41+
{
42+
params_ = param_listener_->get_params();
43+
}
44+
catch (const std::exception & e)
45+
{
46+
fprintf(stderr, "Exception thrown during configure stage with message: %s \n", e.what());
47+
return false;
48+
}
49+
3850
// parse read-only params
39-
num_cmd_joints_ = command_joint_names_.size();
51+
num_cmd_joints_ = params_.command_joints.size();
4052
if (num_cmd_joints_ == 0)
4153
{
4254
RCLCPP_ERROR(node_->get_logger(), "[PidTrajectoryPlugin] No command joints specified.");
@@ -46,7 +58,14 @@ bool PidTrajectoryPlugin::initialize(
4658
ff_velocity_scale_.resize(num_cmd_joints_);
4759

4860
return true;
49-
}
61+
};
62+
63+
bool PidTrajectoryPlugin::activate()
64+
{
65+
params_ = param_listener_->get_params();
66+
updateGains();
67+
return true;
68+
};
5069

5170
bool PidTrajectoryPlugin::updateGainsRT()
5271
{
@@ -59,11 +78,10 @@ bool PidTrajectoryPlugin::updateGainsRT()
5978
return true;
6079
}
6180

62-
bool PidTrajectoryPlugin::computeGainsNonRT(
81+
bool PidTrajectoryPlugin::computeControlLaw(
6382
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & /*trajectory*/)
6483
{
65-
params_ = param_listener_->get_params();
66-
updateGains();
84+
// nothing to do
6785
return true;
6886
};
6987

@@ -72,10 +90,10 @@ void PidTrajectoryPlugin::updateGains()
7290
for (size_t i = 0; i < num_cmd_joints_; ++i)
7391
{
7492
RCLCPP_DEBUG(
75-
node_->get_logger(), "[PidTrajectoryPlugin] command_joint_names_ %lu : %s", i,
76-
command_joint_names_[i].c_str());
93+
node_->get_logger(), "[PidTrajectoryPlugin] params_.command_joints %lu : %s", i,
94+
params_.command_joints[i].c_str());
7795

78-
const auto & gains = params_.gains.command_joints_map.at(command_joint_names_[i]);
96+
const auto & gains = params_.gains.command_joints_map.at(params_.command_joints[i]);
7997
pids_[i] = std::make_shared<control_toolbox::Pid>(
8098
gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
8199
ff_velocity_scale_[i] = gains.ff_velocity_scale;

joint_trajectory_controller_plugins/test/test_pid_trajectory.cpp

Lines changed: 14 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ TEST_F(PidTrajectoryTest, TestEmptySetup)
1919
std::shared_ptr<TestableJointTrajectoryControllerPlugin> traj_contr =
2020
std::make_shared<TestableJointTrajectoryControllerPlugin>();
2121

22-
ASSERT_FALSE(traj_contr->initialize(node_, std::vector<std::string>()));
22+
ASSERT_FALSE(traj_contr->initialize(node_));
2323
}
2424

2525
TEST_F(PidTrajectoryTest, TestSingleJoint)
@@ -30,17 +30,15 @@ TEST_F(PidTrajectoryTest, TestSingleJoint)
3030
std::vector<std::string> joint_names = {"joint1"};
3131
auto joint_names_paramv = rclcpp::ParameterValue(joint_names);
3232

33-
// override read_only parameter
33+
// override parameter
3434
node_->declare_parameter("command_joints", joint_names_paramv);
3535

36-
ASSERT_TRUE(traj_contr->initialize(node_, joint_names));
37-
38-
// set dynamic parameters
39-
traj_contr->trigger_declare_parameters();
36+
ASSERT_TRUE(traj_contr->initialize(node_));
4037
node_->set_parameter(rclcpp::Parameter("gains.joint1.p", 1.0));
41-
38+
ASSERT_TRUE(traj_contr->configure());
39+
ASSERT_TRUE(traj_contr->activate());
4240
ASSERT_TRUE(
43-
traj_contr->computeGainsNonRT(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
41+
traj_contr->computeControlLawNonRT(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
4442
ASSERT_TRUE(traj_contr->updateGainsRT());
4543

4644
trajectory_msgs::msg::JointTrajectoryPoint traj_msg;
@@ -62,19 +60,22 @@ TEST_F(PidTrajectoryTest, TestMultipleJoints)
6260
std::vector<std::string> joint_names = {"joint1", "joint2", "joint3"};
6361
auto joint_names_paramv = rclcpp::ParameterValue(joint_names);
6462

65-
// override read_only parameter
63+
// override parameter
6664
node_->declare_parameter("command_joints", joint_names_paramv);
6765

68-
ASSERT_TRUE(traj_contr->initialize(node_, joint_names));
69-
66+
ASSERT_TRUE(traj_contr->initialize(node_));
7067
// set dynamic parameters
71-
traj_contr->trigger_declare_parameters();
7268
node_->set_parameter(rclcpp::Parameter("gains.joint1.p", 1.0));
7369
node_->set_parameter(rclcpp::Parameter("gains.joint2.p", 2.0));
7470
node_->set_parameter(rclcpp::Parameter("gains.joint3.p", 3.0));
71+
ASSERT_TRUE(traj_contr->configure());
72+
ASSERT_TRUE(traj_contr->activate());
73+
ASSERT_TRUE(
74+
traj_contr->computeControlLawNonRT(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
75+
ASSERT_TRUE(traj_contr->updateGainsRT());
7576

7677
ASSERT_TRUE(
77-
traj_contr->computeGainsNonRT(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
78+
traj_contr->computeControlLawNonRT(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
7879
ASSERT_TRUE(traj_contr->updateGainsRT());
7980

8081
trajectory_msgs::msg::JointTrajectoryPoint traj_msg;

0 commit comments

Comments
 (0)