use swing all rather than stance all

This commit is contained in:
Huang Zhenbiao 2024-09-20 22:10:43 +08:00
parent 269e3b6a3d
commit da99daa31c
4 changed files with 23 additions and 22 deletions

View File

@ -52,6 +52,7 @@ void StateBalanceTest::run() {
} }
void StateBalanceTest::exit() { void StateBalanceTest::exit() {
wave_generator_.status_ = WaveStatus::SWING_ALL;
} }
FSMStateName StateBalanceTest::checkChange() { FSMStateName StateBalanceTest::checkChange() {

View File

@ -64,7 +64,7 @@ void StateTrotting::run() {
} }
void StateTrotting::exit() { void StateTrotting::exit() {
wave_generator_.status_ = WaveStatus::STANCE_ALL; wave_generator_.status_ = WaveStatus::SWING_ALL;
} }
FSMStateName StateTrotting::checkChange() { FSMStateName StateTrotting::checkChange() {

View File

@ -11,8 +11,8 @@
WaveGenerator::WaveGenerator() { WaveGenerator::WaveGenerator() {
phase_past_ << 0.5, 0.5, 0.5, 0.5; phase_past_ << 0.5, 0.5, 0.5, 0.5;
contact_past_.setZero(); contact_past_.setZero();
status_past_ = WaveStatus::STANCE_ALL; status_past_ = WaveStatus::SWING_ALL;
status_ = WaveStatus::STANCE_ALL; status_ = WaveStatus::SWING_ALL;
} }
void WaveGenerator::init(const double period, const double st_ratio, const Vec4 &bias) { void WaveGenerator::init(const double period, const double st_ratio, const Vec4 &bias) {

View File

@ -28,7 +28,7 @@
<gazebo reference="${imu_name}"> <gazebo reference="${imu_name}">
<sensor name="imu_sensor" type="imu"> <sensor name="imu_sensor" type="imu">
<always_on>1</always_on> <always_on>1</always_on>
<update_rate>500</update_rate> <update_rate>1000</update_rate>
<visualize>true</visualize> <visualize>true</visualize>
<topic>imu</topic> <topic>imu</topic>
<imu> <imu>
@ -60,28 +60,28 @@
</angular_velocity> </angular_velocity>
<linear_acceleration> <linear_acceleration>
<x> <x>
<noise type="gaussian"> <!-- <noise type="gaussian">-->
<mean>0.0</mean> <!-- <mean>0.0</mean>-->
<stddev>1.7e-2</stddev> <!-- <stddev>1.7e-2</stddev>-->
<bias_mean>0.1</bias_mean> <!-- <bias_mean>0.1</bias_mean>-->
<bias_stddev>0.001</bias_stddev> <!-- <bias_stddev>0.001</bias_stddev>-->
</noise> <!-- </noise>-->
</x> </x>
<y> <y>
<noise type="gaussian"> <!-- <noise type="gaussian">-->
<mean>0.0</mean> <!-- <mean>0.0</mean>-->
<stddev>1.7e-2</stddev> <!-- <stddev>1.7e-2</stddev>-->
<bias_mean>0.1</bias_mean> <!-- <bias_mean>0.1</bias_mean>-->
<bias_stddev>0.001</bias_stddev> <!-- <bias_stddev>0.001</bias_stddev>-->
</noise> <!-- </noise>-->
</y> </y>
<z> <z>
<noise type="gaussian"> <!-- <noise type="gaussian">-->
<mean>0.0</mean> <!-- <mean>0.0</mean>-->
<stddev>1.7e-2</stddev> <!-- <stddev>1.7e-2</stddev>-->
<bias_mean>0.1</bias_mean> <!-- <bias_mean>0.1</bias_mean>-->
<bias_stddev>0.001</bias_stddev> <!-- <bias_stddev>0.001</bias_stddev>-->
</noise> <!-- </noise>-->
</z> </z>
</linear_acceleration> </linear_acceleration>
</imu> </imu>