Skip to content

Commit 9f0207a

Browse files
Pass scaling factor to plugin
1 parent 345a926 commit 9f0207a

File tree

6 files changed

+25
-8
lines changed

6 files changed

+25
-8
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -335,10 +335,12 @@ controller_interface::return_type JointTrajectoryController::update(
335335
{
336336
if (traj_contr_)
337337
{
338+
double scaling_fact = scaling_factor_.load();
338339
traj_contr_->compute_commands(
339-
tmp_command_, state_current_, state_error_, command_next_,
340+
tmp_command_, scaling_fact, state_current_, state_error_, command_next_,
340341
traj_ctr_state_interfaces_values_, time - current_trajectory_->time_from_start(),
341342
period);
343+
scaling_factor_.store(scaling_fact);
342344
}
343345

344346
// set values for next hardware write()

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -487,15 +487,20 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)
487487
rclcpp::Duration duration_since_start(std::chrono::milliseconds(250));
488488
rclcpp::Duration period(std::chrono::milliseconds(100));
489489

490-
pids->compute_commands(tmp_command, current, error, desired, {}, duration_since_start, period);
490+
double scaling_fact = 1.0;
491+
pids->compute_commands(
492+
tmp_command, scaling_fact, current, error, desired, {}, duration_since_start, period);
491493
EXPECT_EQ(tmp_command.at(0), 0.0);
494+
EXPECT_EQ(scaling_fact, 1.0);
492495

493496
double kp = 1.0;
494497
SetPidParameters(kp);
495498
updateControllerAsync();
496499

497-
pids->compute_commands(tmp_command, current, error, desired, {}, duration_since_start, period);
500+
pids->compute_commands(
501+
tmp_command, scaling_fact, current, error, desired, {}, duration_since_start, period);
498502
EXPECT_EQ(tmp_command.at(0), 1.0);
503+
EXPECT_EQ(scaling_fact, 1.0);
499504
}
500505
else
501506
{

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/pid_trajectory_plugin.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,8 @@ class PidTrajectoryPlugin : public TrajectoryControllerBase
3535
bool update_gains_rt() override;
3636

3737
void compute_commands(
38-
std::vector<double> & tmp_command, const trajectory_msgs::msg::JointTrajectoryPoint current,
38+
std::vector<double> & tmp_command, double & scaling_fact,
39+
const trajectory_msgs::msg::JointTrajectoryPoint current,
3940
const trajectory_msgs::msg::JointTrajectoryPoint error,
4041
const trajectory_msgs::msg::JointTrajectoryPoint desired,
4142
const std::vector<double> & opt_state_interfaces_values_,

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/trajectory_controller_base.hpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -127,15 +127,19 @@ class TrajectoryControllerBase
127127
* @brief compute the commands with the precalculated control law
128128
*
129129
* @param[out] tmp_command the output command
130+
* @param[out] scaling_fact scaling factor if ctrl is not following reference
130131
* @param[in] current the current state
131132
* @param[in] error the error between the current state and the desired state
132133
* @param[in] desired the desired state
134+
* @param[in] opt_state_interfaces_values_ optional state interface values, \ref
135+
* state_interface_configuration
133136
* @param[in] duration_since_start the duration since the start of the trajectory
134137
* can be negative if the trajectory-start is in the future
135138
* @param[in] period the period since the last update
136139
*/
137140
virtual void compute_commands(
138-
std::vector<double> & tmp_command, const trajectory_msgs::msg::JointTrajectoryPoint current,
141+
std::vector<double> & tmp_command, double & scaling_fact,
142+
const trajectory_msgs::msg::JointTrajectoryPoint current,
139143
const trajectory_msgs::msg::JointTrajectoryPoint error,
140144
const trajectory_msgs::msg::JointTrajectoryPoint desired,
141145
const std::vector<double> & opt_state_interfaces_values_,

joint_trajectory_controller_plugins/src/pid_trajectory_plugin.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,8 @@ void PidTrajectoryPlugin::parse_gains()
113113
}
114114

115115
void PidTrajectoryPlugin::compute_commands(
116-
std::vector<double> & tmp_command, const trajectory_msgs::msg::JointTrajectoryPoint /*current*/,
116+
std::vector<double> & tmp_command, double & /*scaling_fact*/,
117+
const trajectory_msgs::msg::JointTrajectoryPoint /*current*/,
117118
const trajectory_msgs::msg::JointTrajectoryPoint error,
118119
const trajectory_msgs::msg::JointTrajectoryPoint desired,
119120
const std::vector<double> & /* opt_state_interfaces_values_*/,

joint_trajectory_controller_plugins/test/test_pid_trajectory.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -50,8 +50,10 @@ TEST_F(PidTrajectoryTest, TestSingleJoint)
5050
const rclcpp::Duration time_since_start(1, 0);
5151
const rclcpp::Duration period(1, 0);
5252

53+
double scaling_fact = 1.0;
5354
ASSERT_NO_THROW(traj_contr->compute_commands(
54-
tmp_command, traj_msg, traj_msg, traj_msg, {}, time_since_start, period));
55+
tmp_command, scaling_fact, traj_msg, traj_msg, traj_msg, {}, time_since_start, period));
56+
EXPECT_EQ(scaling_fact, 1.0);
5557
}
5658

5759
TEST_F(PidTrajectoryTest, TestMultipleJoints)
@@ -92,8 +94,10 @@ TEST_F(PidTrajectoryTest, TestMultipleJoints)
9294
const rclcpp::Duration time_since_start(1, 0);
9395
const rclcpp::Duration period(1, 0);
9496

97+
double scaling_fact = 1.0;
9598
ASSERT_NO_THROW(traj_contr->compute_commands(
96-
tmp_command, traj_msg, traj_msg, traj_msg, {}, time_since_start, period));
99+
tmp_command, scaling_fact, traj_msg, traj_msg, traj_msg, {}, time_since_start, period));
100+
EXPECT_EQ(scaling_fact, 1.0);
97101

98102
EXPECT_EQ(tmp_command[0], 1.0);
99103
EXPECT_EQ(tmp_command[1], 2.0);

0 commit comments

Comments
 (0)