Skip to content

Commit 21764c7

Browse files
Remove local vars and just call compute-commands with duration in trajectory
1 parent 8bc3e16 commit 21764c7

File tree

5 files changed

+37
-41
lines changed

5 files changed

+37
-41
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -227,7 +227,7 @@ controller_interface::return_type JointTrajectoryController::update(
227227
if (traj_contr_)
228228
{
229229
// set start time of trajectory to traj_contr_
230-
traj_contr_->start(time, traj_external_point_ptr_->time_from_start());
230+
traj_contr_->start();
231231
}
232232
}
233233

@@ -304,7 +304,8 @@ controller_interface::return_type JointTrajectoryController::update(
304304
if (traj_contr_)
305305
{
306306
traj_contr_->computeCommands(
307-
tmp_command_, state_current_, state_error_, state_desired_, time, period);
307+
tmp_command_, state_current_, state_error_, state_desired_,
308+
time - traj_external_point_ptr_->time_from_start(), period);
308309
}
309310

310311
// set values for next hardware write()

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/pid_trajectory_plugin.hpp

Lines changed: 12 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -40,18 +40,27 @@ class PidTrajectoryPlugin : public TrajectoryControllerBase
4040
bool activate() override;
4141

4242
bool computeControlLaw(
43-
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & /*trajectory*/) override;
43+
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & /*trajectory*/) override
44+
{
45+
// nothing to do
46+
return true;
47+
}
4448

4549
bool updateGainsRT() override;
4650

4751
void computeCommands(
4852
std::vector<double> & tmp_command, const trajectory_msgs::msg::JointTrajectoryPoint current,
4953
const trajectory_msgs::msg::JointTrajectoryPoint error,
50-
const trajectory_msgs::msg::JointTrajectoryPoint desired, const rclcpp::Time & time,
51-
const rclcpp::Duration & period) override;
54+
const trajectory_msgs::msg::JointTrajectoryPoint desired,
55+
const rclcpp::Duration & duration_since_start, const rclcpp::Duration & period) override;
5256

5357
void reset() override;
5458

59+
void start() override
60+
{
61+
// nothing to do
62+
}
63+
5564
protected:
5665
/**
5766
* @brief parse PID gains from parameter struct

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/trajectory_controller_base.hpp

Lines changed: 14 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -82,22 +82,11 @@ class TrajectoryControllerBase
8282
}
8383

8484
/**
85-
* @brief set the time when the current trajectory started
85+
* @brief called when the current trajectory started in update loop
8686
*
87-
* (same logic as trajectory class)
87+
* use this to implement switching of real-time buffers for updating the control law
8888
*/
89-
void start(const rclcpp::Time time, const rclcpp::Time trajectory_start_time)
90-
{
91-
if (trajectory_start_time.seconds() == 0.0)
92-
{
93-
trajectory_start_time_ = time;
94-
}
95-
else
96-
{
97-
trajectory_start_time_ = trajectory_start_time;
98-
}
99-
start_trajectory_ = true;
100-
}
89+
virtual void start(void) = 0;
10190

10291
/**
10392
* @brief update the gains from a RT thread
@@ -110,14 +99,22 @@ class TrajectoryControllerBase
11099
virtual bool updateGainsRT(void) = 0;
111100

112101
/**
113-
* @brief compute the commands with the calculated gains
102+
* @brief compute the commands with the precalculated control law
103+
*
104+
* @param[out] tmp_command the output command
105+
* @param[in] current the current state
106+
* @param[in] error the error between the current state and the desired state
107+
* @param[in] desired the desired state
108+
* @param[in] duration_since_start the duration since the start of the trajectory
109+
* can be negative if the trajectory-start is in the future
110+
* @param[in] period the period since the last update
114111
*/
115112
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
116113
virtual void computeCommands(
117114
std::vector<double> & tmp_command, const trajectory_msgs::msg::JointTrajectoryPoint current,
118115
const trajectory_msgs::msg::JointTrajectoryPoint error,
119-
const trajectory_msgs::msg::JointTrajectoryPoint desired, const rclcpp::Time & time,
120-
const rclcpp::Duration & period) = 0;
116+
const trajectory_msgs::msg::JointTrajectoryPoint desired,
117+
const rclcpp::Duration & duration_since_start, const rclcpp::Duration & period) = 0;
121118

122119
/**
123120
* @brief reset internal states
@@ -136,10 +133,6 @@ class TrajectoryControllerBase
136133
rclcpp_lifecycle::LifecycleNode::SharedPtr node_;
137134
// Are we computing the control law or is it valid?
138135
realtime_tools::RealtimeBuffer<bool> rt_control_law_ready_;
139-
// time when the current trajectory started, can be used to interpolate time-varying gains
140-
rclcpp::Time trajectory_start_time_;
141-
// use this variable to activate new gains from the non-RT thread
142-
bool start_trajectory_ = false;
143136

144137
/**
145138
* @brief compute the control law from the given trajectory

joint_trajectory_controller_plugins/src/pid_trajectory_plugin.cpp

Lines changed: 2 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -78,13 +78,6 @@ bool PidTrajectoryPlugin::updateGainsRT()
7878
return true;
7979
}
8080

81-
bool PidTrajectoryPlugin::computeControlLaw(
82-
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & /*trajectory*/)
83-
{
84-
// nothing to do
85-
return true;
86-
};
87-
8881
void PidTrajectoryPlugin::updateGains()
8982
{
9083
for (size_t i = 0; i < num_cmd_joints_; ++i)
@@ -112,8 +105,8 @@ void PidTrajectoryPlugin::updateGains()
112105
void PidTrajectoryPlugin::computeCommands(
113106
std::vector<double> & tmp_command, const trajectory_msgs::msg::JointTrajectoryPoint /*current*/,
114107
const trajectory_msgs::msg::JointTrajectoryPoint error,
115-
const trajectory_msgs::msg::JointTrajectoryPoint desired, const rclcpp::Time & /*time*/,
116-
const rclcpp::Duration & period)
108+
const trajectory_msgs::msg::JointTrajectoryPoint desired,
109+
const rclcpp::Duration & /*duration_since_start*/, const rclcpp::Duration & period)
117110
{
118111
// Update PIDs
119112
for (auto i = 0ul; i < num_cmd_joints_; ++i)

joint_trajectory_controller_plugins/test/test_pid_trajectory.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -45,11 +45,11 @@ TEST_F(PidTrajectoryTest, TestSingleJoint)
4545
traj_msg.positions.push_back(0.0);
4646
traj_msg.velocities.push_back(0.0);
4747
std::vector<double> tmp_command(1, 0.0);
48-
const rclcpp::Time time;
48+
const rclcpp::Duration time_since_start(1, 0);
4949
const rclcpp::Duration period(1, 0);
5050

51-
ASSERT_NO_THROW(
52-
traj_contr->computeCommands(tmp_command, traj_msg, traj_msg, traj_msg, time, period));
51+
ASSERT_NO_THROW(traj_contr->computeCommands(
52+
tmp_command, traj_msg, traj_msg, traj_msg, time_since_start, period));
5353
}
5454

5555
TEST_F(PidTrajectoryTest, TestMultipleJoints)
@@ -86,11 +86,11 @@ TEST_F(PidTrajectoryTest, TestMultipleJoints)
8686
traj_msg.velocities.push_back(0.0);
8787
traj_msg.velocities.push_back(0.0);
8888
std::vector<double> tmp_command(3, 0.0);
89-
const rclcpp::Time time;
89+
const rclcpp::Duration time_since_start(1, 0);
9090
const rclcpp::Duration period(1, 0);
9191

92-
ASSERT_NO_THROW(
93-
traj_contr->computeCommands(tmp_command, traj_msg, traj_msg, traj_msg, time, period));
92+
ASSERT_NO_THROW(traj_contr->computeCommands(
93+
tmp_command, traj_msg, traj_msg, traj_msg, time_since_start, period));
9494

9595
EXPECT_EQ(tmp_command[0], 1.0);
9696
EXPECT_EQ(tmp_command[1], 2.0);

0 commit comments

Comments
 (0)