@@ -215,21 +215,21 @@ class TrajectoryControllerTest : public ::testing::Test
215
215
}
216
216
217
217
void SetPidParameters (
218
- double p_default = 0.0 , double ff_default = 1.0 , bool angle_wraparound_default = false )
218
+ double p_value = 0.0 , double ff_value = 1.0 , bool angle_wraparound_value = false )
219
219
{
220
220
traj_controller_->trigger_declare_parameters ();
221
221
auto node = traj_controller_->get_node ();
222
222
223
223
for (size_t i = 0 ; i < joint_names_.size (); ++i)
224
224
{
225
225
const std::string prefix = " gains." + joint_names_[i];
226
- const rclcpp::Parameter k_p (prefix + " .p" , p_default );
226
+ const rclcpp::Parameter k_p (prefix + " .p" , p_value );
227
227
const rclcpp::Parameter k_i (prefix + " .i" , 0.0 );
228
228
const rclcpp::Parameter k_d (prefix + " .d" , 0.0 );
229
229
const rclcpp::Parameter i_clamp (prefix + " .i_clamp" , 0.0 );
230
- const rclcpp::Parameter ff_velocity_scale (prefix + " .ff_velocity_scale" , ff_default );
230
+ const rclcpp::Parameter ff_velocity_scale (prefix + " .ff_velocity_scale" , ff_value );
231
231
const rclcpp::Parameter angle_wraparound (
232
- prefix + " .angle_wraparound" , angle_wraparound_default );
232
+ prefix + " .angle_wraparound" , angle_wraparound_value );
233
233
node->set_parameters ({k_p, k_i, k_d, i_clamp, ff_velocity_scale, angle_wraparound});
234
234
}
235
235
}
0 commit comments