Skip to content

Commit 70cf724

Browse files
Split non-RT and RT methods
1 parent 732dfaf commit 70cf724

File tree

6 files changed

+86
-24
lines changed

6 files changed

+86
-24
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 19 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -134,6 +134,18 @@ controller_interface::return_type JointTrajectoryController::update(
134134
}
135135
}
136136

137+
// update gains of controller
138+
// TODO(christophfroehlich) activate this
139+
// once https://github.com/ros-controls/ros2_controllers/pull/761 is merged
140+
// if (use_closed_loop_control_law_)
141+
// {
142+
// if(traj_contr_->updateGainsRT() == false)
143+
// {
144+
// RCLCPP_ERROR(get_node()->get_logger(), "Could not update gains of controller");
145+
// return controller_interface::return_type::ERROR;
146+
// }
147+
// }
148+
137149
auto compute_error_for_joint = [&](
138150
JointTrajectoryPoint & error, size_t index,
139151
const JointTrajectoryPoint & current,
@@ -170,6 +182,7 @@ controller_interface::return_type JointTrajectoryController::update(
170182
auto current_external_msg = traj_external_point_ptr_->get_trajectory_msg();
171183
auto new_external_msg = traj_msg_external_point_ptr_.readFromRT();
172184
// Discard, if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
185+
// TODO(christophfroehlich) wait until gains were computed by the trajectory controller
173186
if (
174187
current_external_msg != *new_external_msg &&
175188
(*(rt_has_pending_goal_.readFromRT()) && !active_goal) == false)
@@ -704,7 +717,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
704717
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_EFFORT);
705718

706719
// if there is only velocity or if there is effort command interface
707-
// then use also closed loop controller
720+
// then use also closed-loop controller
708721
use_closed_loop_control_law_ =
709722
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1 &&
710723
!params_.open_loop_control) ||
@@ -1490,10 +1503,13 @@ void JointTrajectoryController::add_new_trajectory_msg(
14901503
{
14911504
traj_msg_external_point_ptr_.writeFromNonRT(traj_msg);
14921505

1493-
// update gains of controller
1506+
// compute gains of controller
14941507
if (use_closed_loop_control_law_)
14951508
{
1496-
traj_contr_->computeGains(traj_msg);
1509+
if (traj_contr_->computeGainsNonRT(traj_msg) == false)
1510+
{
1511+
RCLCPP_ERROR(get_node()->get_logger(), "Failed to compute gains for trajectory.");
1512+
}
14971513
}
14981514
}
14991515

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -217,6 +217,7 @@ class TrajectoryControllerTest : public ::testing::Test
217217
traj_controller_->trigger_declare_parameters();
218218
auto node = traj_controller_->get_node();
219219

220+
// TODO(christophfroehlich): use command joints instead of joint_names
220221
for (size_t i = 0; i < joint_names_.size(); ++i)
221222
{
222223
const std::string prefix = "gains." + joint_names_[i];

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/pid_trajectory_plugin.hpp

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,10 @@ class PidTrajectoryPlugin : public TrajectoryControllerBase
3737
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
3838
std::vector<std::string> command_joint_names) override;
3939

40-
bool computeGains(
41-
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & trajectory) override;
40+
bool computeGainsNonRT(
41+
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & /*trajectory*/) override;
42+
43+
bool updateGainsRT() override;
4244

4345
void computeCommands(
4446
std::vector<double> & tmp_command, const trajectory_msgs::msg::JointTrajectoryPoint current,
@@ -49,6 +51,11 @@ class PidTrajectoryPlugin : public TrajectoryControllerBase
4951
void reset() override;
5052

5153
protected:
54+
/**
55+
* @brief parse PID gains from parameter struct
56+
*/
57+
void updateGains();
58+
5259
// number of command joints
5360
size_t num_cmd_joints_;
5461
// name of the command joints

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/trajectory_controller_base.hpp

Lines changed: 18 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,19 +39,35 @@ class TrajectoryControllerBase
3939
virtual ~TrajectoryControllerBase() = default;
4040

4141
/**
42+
* @brief initialize the controller plugin.
43+
* parse read-only parameters and do pre-allocate memory for the controller
4244
*/
4345
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
4446
virtual bool initialize(
4547
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
4648
std::vector<std::string> command_joint_names) = 0;
4749

4850
/**
51+
* @brief compute the gains from the given trajectory from a non-RT thread
52+
* @return true if the gains were computed, false otherwise
4953
*/
5054
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
51-
virtual bool computeGains(
55+
virtual bool computeGainsNonRT(
5256
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & trajectory) = 0;
5357

5458
/**
59+
* @brief update the gains from the given trajectory from a RT thread
60+
*
61+
* this method must finish quickly (within one controller-update rate,
62+
* and should not allocate memory
63+
*
64+
* @return true if the gains were updated, false otherwise
65+
*/
66+
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
67+
virtual bool updateGainsRT(void) = 0;
68+
69+
/**
70+
* @brief compute the commands with the calculated gains
5571
*/
5672
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
5773
virtual void computeCommands(
@@ -61,6 +77,7 @@ class TrajectoryControllerBase
6177
const rclcpp::Duration & period) = 0;
6278

6379
/**
80+
* @brief reset internal states
6481
*/
6582
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
6683
virtual void reset() = 0;

joint_trajectory_controller_plugins/src/pid_trajectory_plugin.cpp

Lines changed: 24 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -45,37 +45,50 @@ bool PidTrajectoryPlugin::initialize(
4545
pids_.resize(num_cmd_joints_);
4646
ff_velocity_scale_.resize(num_cmd_joints_);
4747

48-
RCLCPP_INFO(
49-
node_->get_logger(), "[PidTrajectoryPlugin] Initialized with %lu joints.", num_cmd_joints_);
5048
return true;
5149
}
5250

53-
bool PidTrajectoryPlugin::computeGains(
54-
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & /*trajectory*/)
51+
bool PidTrajectoryPlugin::updateGainsRT()
5552
{
5653
if (param_listener_->is_old(params_))
5754
{
5855
params_ = param_listener_->get_params();
59-
RCLCPP_DEBUG(node_->get_logger(), "[PidTrajectoryPlugin] Updated parameters");
56+
updateGains();
6057
}
6158

62-
pids_.resize(num_cmd_joints_);
63-
ff_velocity_scale_.resize(num_cmd_joints_);
59+
return true;
60+
}
6461

65-
// Init PID gains from ROS parameters
62+
bool PidTrajectoryPlugin::computeGainsNonRT(
63+
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & /*trajectory*/)
64+
{
65+
params_ = param_listener_->get_params();
66+
updateGains();
67+
return true;
68+
};
69+
70+
void PidTrajectoryPlugin::updateGains()
71+
{
6672
for (size_t i = 0; i < num_cmd_joints_; ++i)
6773
{
74+
RCLCPP_DEBUG(
75+
node_->get_logger(), "[PidTrajectoryPlugin] command_joint_names_ %lu : %s", i,
76+
command_joint_names_[i].c_str());
77+
6878
const auto & gains = params_.gains.joints_map.at(command_joint_names_[i]);
6979
pids_[i] = std::make_shared<control_toolbox::Pid>(
7080
gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
71-
7281
ff_velocity_scale_[i] = gains.ff_velocity_scale;
82+
83+
RCLCPP_DEBUG(node_->get_logger(), "[PidTrajectoryPlugin] gains.p: %f", gains.p);
84+
RCLCPP_DEBUG(
85+
node_->get_logger(), "[PidTrajectoryPlugin] ff_velocity_scale_: %f", ff_velocity_scale_[i]);
7386
}
7487

7588
RCLCPP_INFO(
7689
node_->get_logger(),
77-
"[PidTrajectoryPlugin] Loaded PID gains from ROS parameters for %lu joints.", num_cmd_joints_);
78-
return true;
90+
"[PidTrajectoryPlugin] Loaded PID gains from ROS parameters for %lu joint(s).",
91+
num_cmd_joints_);
7992
}
8093

8194
void PidTrajectoryPlugin::computeCommands(

joint_trajectory_controller_plugins/test/test_pid_trajectory.cpp

Lines changed: 15 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,9 @@ TEST_F(PidTrajectoryTest, TestSingleJoint)
3939
traj_contr->trigger_declare_parameters();
4040
node_->set_parameter(rclcpp::Parameter("gains.joint1.p", 1.0));
4141

42-
ASSERT_TRUE(traj_contr->computeGains(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
42+
ASSERT_TRUE(
43+
traj_contr->computeGainsNonRT(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
44+
ASSERT_TRUE(traj_contr->updateGainsRT());
4345

4446
trajectory_msgs::msg::JointTrajectoryPoint traj_msg;
4547
traj_msg.positions.push_back(0.0);
@@ -68,15 +70,17 @@ TEST_F(PidTrajectoryTest, TestMultipleJoints)
6870
// set dynamic parameters
6971
traj_contr->trigger_declare_parameters();
7072
node_->set_parameter(rclcpp::Parameter("gains.joint1.p", 1.0));
71-
node_->set_parameter(rclcpp::Parameter("gains.joint2.p", 1.0));
72-
node_->set_parameter(rclcpp::Parameter("gains.joint3.p", 1.0));
73+
node_->set_parameter(rclcpp::Parameter("gains.joint2.p", 2.0));
74+
node_->set_parameter(rclcpp::Parameter("gains.joint3.p", 3.0));
7375

74-
ASSERT_TRUE(traj_contr->computeGains(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
76+
ASSERT_TRUE(
77+
traj_contr->computeGainsNonRT(std::make_shared<trajectory_msgs::msg::JointTrajectory>()));
78+
ASSERT_TRUE(traj_contr->updateGainsRT());
7579

7680
trajectory_msgs::msg::JointTrajectoryPoint traj_msg;
77-
traj_msg.positions.push_back(0.0);
78-
traj_msg.positions.push_back(0.0);
79-
traj_msg.positions.push_back(0.0);
81+
traj_msg.positions.push_back(1.0);
82+
traj_msg.positions.push_back(1.0);
83+
traj_msg.positions.push_back(1.0);
8084
traj_msg.velocities.push_back(0.0);
8185
traj_msg.velocities.push_back(0.0);
8286
traj_msg.velocities.push_back(0.0);
@@ -86,6 +90,10 @@ TEST_F(PidTrajectoryTest, TestMultipleJoints)
8690

8791
ASSERT_NO_THROW(
8892
traj_contr->computeCommands(tmp_command, traj_msg, traj_msg, traj_msg, time, period));
93+
94+
EXPECT_EQ(tmp_command[0], 1.0);
95+
EXPECT_EQ(tmp_command[1], 2.0);
96+
EXPECT_EQ(tmp_command[2], 3.0);
8997
}
9098

9199
int main(int argc, char ** argv)

0 commit comments

Comments
 (0)