Skip to content

Commit 20845eb

Browse files
committed
refactor(control_toolbox): fix deprecated PID methods
after changes in ros-controls/control_toolbox#246
1 parent d6338e8 commit 20845eb

File tree

3 files changed

+12
-12
lines changed

3 files changed

+12
-12
lines changed

bitbots_motion/bitbots_dynamic_kick/src/stabilizer.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -23,8 +23,8 @@ Stabilizer::Stabilizer(std::string ns) {
2323

2424
pid_trunk_fused_pitch_ = std::make_shared<control_toolbox::PidROS>(pitch_node_, "");
2525
pid_trunk_fused_roll_ = std::make_shared<control_toolbox::PidROS>(roll_node_, "");
26-
pid_trunk_fused_pitch_->initPid();
27-
pid_trunk_fused_roll_->initPid();
26+
pid_trunk_fused_pitch_->initialize_from_ros_parameters();
27+
pid_trunk_fused_roll_->initialize_from_ros_parameters();
2828

2929
reset();
3030
}
@@ -51,8 +51,8 @@ KickPositions Stabilizer::stabilize(const KickPositions &positions, const rclcpp
5151
cop_x_error = cop_x - positions.trunk_pose.translation().x();
5252
cop_y_error = cop_y - positions.trunk_pose.translation().y();
5353

54-
double x_correction = pid_trunk_fused_roll_->computeCommand(cop_x_error, dt);
55-
double y_correction = pid_trunk_fused_pitch_->computeCommand(cop_y_error, dt);
54+
double x_correction = pid_trunk_fused_roll_->compute_command(cop_x_error, dt);
55+
double y_correction = pid_trunk_fused_pitch_->compute_command(cop_y_error, dt);
5656

5757
stabilized_positions.trunk_pose.translation().x() += x_correction;
5858
stabilized_positions.trunk_pose.translation().y() += y_correction;

bitbots_motion/bitbots_dynup/src/dynup_stabilizer.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,8 @@ Stabilizer::Stabilizer(rclcpp::Node::SharedPtr node, bitbots_dynup::Params::Stab
66
: params_(params),
77
pid_trunk_pitch_(node, "stabilizer.trunk_pid.pitch"),
88
pid_trunk_roll_(node, "stabilizer.trunk_pid.roll") {
9-
pid_trunk_pitch_.initPid();
10-
pid_trunk_roll_.initPid();
9+
pid_trunk_pitch_.initialize_from_ros_parameters();
10+
pid_trunk_roll_.initialize_from_ros_parameters();
1111

1212
reset();
1313
}
@@ -43,8 +43,8 @@ DynupResponse Stabilizer::stabilize(const DynupResponse &ik_goals, const rclcpp:
4343

4444
// Adapt trunk based on PID controller
4545
goal_fused.fusedPitch +=
46-
pid_trunk_pitch_.computeCommand(goal_fused.fusedPitch - current_orientation.fusedPitch, dt);
47-
goal_fused.fusedRoll += pid_trunk_roll_.computeCommand(goal_fused.fusedRoll - current_orientation.fusedRoll, dt);
46+
pid_trunk_pitch_.compute_command(goal_fused.fusedPitch - current_orientation.fusedPitch, dt);
47+
goal_fused.fusedRoll += pid_trunk_roll_.compute_command(goal_fused.fusedRoll - current_orientation.fusedRoll, dt);
4848

4949
// Check if the trunk is stable, meaning it isn't leaning too much
5050
// TODO it would be better to use the rotational velocity of the imu to determine stability

bitbots_motion/bitbots_quintic_walk/src/walk_stabilizer.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,8 @@ namespace bitbots_quintic_walk {
44

55
WalkStabilizer::WalkStabilizer(rclcpp::Node::SharedPtr node)
66
: pid_trunk_fused_pitch_(node, "node.trunk_pid.pitch"), pid_trunk_fused_roll_(node, "node.trunk_pid.roll") {
7-
pid_trunk_fused_pitch_.initPid();
8-
pid_trunk_fused_roll_.initPid();
7+
pid_trunk_fused_pitch_.initialize_from_ros_parameters();
8+
pid_trunk_fused_roll_.initialize_from_ros_parameters();
99

1010
reset();
1111
}
@@ -29,9 +29,9 @@ WalkResponse WalkStabilizer::stabilize(const WalkResponse& response, const rclcp
2929

3030
// adapt trunk values based on PID controllers
3131
double fused_roll_correction =
32-
pid_trunk_fused_roll_.computeCommand(goal_fused.fusedRoll - response.current_fused_roll, dt);
32+
pid_trunk_fused_roll_.compute_command(goal_fused.fusedRoll - response.current_fused_roll, dt);
3333
double fused_pitch_correction =
34-
pid_trunk_fused_pitch_.computeCommand(goal_fused.fusedPitch - response.current_fused_pitch, dt);
34+
pid_trunk_fused_pitch_.compute_command(goal_fused.fusedPitch - response.current_fused_pitch, dt);
3535

3636
// Change trunk x offset (in the trunks frame of reference) based on the PID controllers
3737
WalkResponse stabilized_response{response};

0 commit comments

Comments
 (0)