Skip to content

Commit ee9b43e

Browse files
committed
Changes to the way parameters are handled. Also Setups regarding ML
1 parent 1eef281 commit ee9b43e

File tree

6 files changed

+42
-12
lines changed

6 files changed

+42
-12
lines changed

bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml

+3-1
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ walking:
7575
phase_reset:
7676
min_phase: 0.90
7777
foot_pressure:
78-
active: True
78+
active: False
7979
ground_min_pressure: 1.5
8080
effort:
8181
active: False
@@ -107,10 +107,12 @@ walking:
107107
i_clamp_min: 0.0
108108
i_clamp_max: 0.0
109109
antiwindup: False
110+
threshold: 0.0
110111
roll:
111112
p: 0.0
112113
i: 0.0
113114
d: 0.0
114115
i_clamp_min: 0.0
115116
i_clamp_max: 0.0
116117
antiwindup: False
118+
threshold: 0.0

bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_stabilizer.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
1414

1515
#include "bitbots_quintic_walk/walk_utils.hpp"
16+
#include "bitbots_quintic_walk_parameters.hpp"
1617
#include "bitbots_splines/abstract_stabilizer.hpp"
1718

1819
namespace bitbots_quintic_walk {
@@ -23,7 +24,8 @@ class WalkStabilizer : public bitbots_splines::AbstractStabilizer<WalkResponse>
2324
void reset() override;
2425
WalkResponse stabilize(const WalkResponse &response, const rclcpp::Duration &dt) override;
2526
WalkRequest adjust_step_length(WalkRequest request, const double imu_roll, const double imu_pitch,
26-
double pitch_threshold, double roll_threshold, const rclcpp::Duration &dt);
27+
double pitch_threshold, double roll_threshold, const rclcpp::Duration &dt,
28+
walking::Params config_);
2729

2830
private:
2931
rclcpp::Node::SharedPtr node_;

bitbots_motion/bitbots_quintic_walk/src/parameters.yaml

+16
Original file line numberDiff line numberDiff line change
@@ -372,11 +372,27 @@ walking:
372372
default_value: false
373373
step_length:
374374
pitch:
375+
p:
376+
type: double
377+
description: "Proportional gain for the step adjust pitch controller"
378+
default_value: 0.0
379+
d:
380+
type: double
381+
description: "Derivative gain for the step adjust pitch controller"
382+
default_value: 0.0
375383
threshold:
376384
type: double
377385
description: "Threshold to trigger step length adjustment"
378386
default_value: 0.0
379387
roll:
388+
p:
389+
type: double
390+
description: "Proportional gain for the step adjust roll controller"
391+
default_value: 0.0
392+
d:
393+
type: double
394+
description: "Derivative gain for the step adjust roll controller"
395+
default_value: 0.0
380396
threshold:
381397
type: double
382398
description: "Threshold to trigger step length adjustment"

bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -181,7 +181,7 @@ bitbots_msgs::msg::JointCommand WalkNode::step(double dt) {
181181
RCLCPP_WARN(node_->get_logger(), "Original step size: %f, %f", request.linear_orders[0], request.linear_orders[1]);
182182
request = stabilizer_.adjust_step_length(
183183
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));
184+
config_.node.step_length.roll.threshold, rclcpp::Duration::from_nanoseconds(1e9 * dt), config_);
185185
RCLCPP_WARN(node_->get_logger(), "New step size: %f, %f", request.linear_orders[0], request.linear_orders[1]);
186186

187187
walk_engine_.setGoals(request);

bitbots_motion/bitbots_quintic_walk/src/walk_stabilizer.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -25,10 +25,12 @@ void WalkStabilizer::reset() {
2525

2626
WalkRequest WalkStabilizer::adjust_step_length(WalkRequest request, const double imu_roll, const double imu_pitch,
2727
double pitch_threshold, double roll_threshold,
28-
const rclcpp::Duration& dt) {
28+
const rclcpp::Duration& dt, walking::Params config_) {
2929
double adjustment_pitch = pid_step_length_adjustment_pitch_.computeCommand(imu_pitch, dt);
3030
double adjustment_roll = pid_step_length_adjustment_roll_.computeCommand(imu_roll, dt);
3131
RCLCPP_WARN(node_->get_logger(), "Adjustment pitch, roll: %f, %f", adjustment_pitch, adjustment_roll);
32+
RCLCPP_WARN(node_->get_logger(), "p: %f,", config_.node.step_length.pitch.p);
33+
3234
// adapt step length values based on PID controllers
3335
// we use a threshold to avoid unneeded steps
3436
if (fabs(adjustment_pitch) >= pitch_threshold) {

bitbots_simulation/bitbots_webots_sim/worlds/optimization_wolfgang.wbt

+16-8
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,11 @@
1-
#VRML_SIM R2021b utf8
1+
#VRML_SIM R2022b utf8
2+
3+
EXTERNPROTO "../protos/robots/Wolfgang/WolfgangOptimization.proto"
4+
#EXTERNPROTO "../protos/robots/Wolfgang/Wolfgang.proto"
5+
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/floors/protos/Floor.proto"
6+
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackground.proto"
7+
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto"
8+
29
DEF world_info WorldInfo {
310
basicTimeStep 8
411
optimalThreadCount 1
@@ -29,7 +36,7 @@ DEF world_info WorldInfo {
2936
]
3037
}
3138
Viewpoint {
32-
orientation 0.14 -0.605 -0.784 2.78
39+
orientation 0.0550798 0.739203 -0.671227 0.221113
3340
position -2.20 4.06 1.5
3441
}
3542
TexturedBackground {
@@ -39,16 +46,17 @@ TexturedBackgroundLight {
3946
texture "stadium_dry"
4047
}
4148

49+
Floor {
50+
rotation 0 1 0 0
51+
contactMaterial "grass"
52+
size 100 100
53+
tileSize 2 2
54+
}
55+
4256
DEF amy WolfgangOptimization {
4357
translation -0.9968797400586715 2.9921102788692946 0.4274542359577024
4458
rotation 0.12198099937775954 0.12935172908461096 -0.9840674600725422 1.5869763401625028
4559
name "amy"
4660
controller "<extern>"
4761
supervisor TRUE
4862
}
49-
Floor {
50-
rotation 1 0 0 1.57
51-
contactMaterial "grass"
52-
size 100 100
53-
tileSize 2 2
54-
}

0 commit comments

Comments
 (0)