Skip to content

Commit 15b367e

Browse files
committed
refactor how walk_stabilizer accesses config values for adjust_step_length()
1 parent ce3a89b commit 15b367e

File tree

3 files changed

+3
-6
lines changed

3 files changed

+3
-6
lines changed

bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_stabilizer.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,7 @@ class WalkStabilizer : public bitbots_splines::AbstractStabilizer<WalkResponse>
2424
void reset() override;
2525
WalkResponse stabilize(const WalkResponse &response, const rclcpp::Duration &dt) override;
2626
WalkRequest adjust_step_length(WalkRequest request, const double imu_roll, const double imu_pitch,
27-
double pitch_threshold, double roll_threshold, const rclcpp::Duration &dt,
28-
walking::Params config_);
27+
const rclcpp::Duration &dt, walking::Params config_);
2928

3029
private:
3130
rclcpp::Node::SharedPtr node_;

bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -179,9 +179,8 @@ bitbots_msgs::msg::JointCommand WalkNode::step(double dt) {
179179

180180
// Apply step length adjustment
181181
RCLCPP_WARN(node_->get_logger(), "Original step size: %f, %f", request.linear_orders[0], request.linear_orders[1]);
182-
request = stabilizer_.adjust_step_length(
183-
request, current_trunk_fused_roll_, current_trunk_fused_pitch_, config_.node.step_length.pitch.threshold,
184-
config_.node.step_length.roll.threshold, rclcpp::Duration::from_nanoseconds(1e9 * dt), config_);
182+
request = stabilizer_.adjust_step_length(request, current_trunk_fused_roll_, current_trunk_fused_pitch_,
183+
rclcpp::Duration::from_nanoseconds(1e9 * dt), config_);
185184
RCLCPP_WARN(node_->get_logger(), "New step size: %f, %f", request.linear_orders[0], request.linear_orders[1]);
186185

187186
walk_engine_.setGoals(request);

bitbots_motion/bitbots_quintic_walk/src/walk_stabilizer.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@ void WalkStabilizer::reset() {
2424
}
2525

2626
WalkRequest WalkStabilizer::adjust_step_length(WalkRequest request, const double imu_roll, const double imu_pitch,
27-
double pitch_threshold, double roll_threshold,
2827
const rclcpp::Duration& dt, walking::Params config_) {
2928
double imu_pitch_adjusted = imu_pitch - config_.engine.trunk_pitch;
3029
double pitch_threshold = config_.node.step_length.pitch.threshold;

0 commit comments

Comments
 (0)