use swing all rather than stance all
This commit is contained in:
parent
269e3b6a3d
commit
da99daa31c
|
@ -52,6 +52,7 @@ void StateBalanceTest::run() {
|
|||
}
|
||||
|
||||
void StateBalanceTest::exit() {
|
||||
wave_generator_.status_ = WaveStatus::SWING_ALL;
|
||||
}
|
||||
|
||||
FSMStateName StateBalanceTest::checkChange() {
|
||||
|
|
|
@ -64,7 +64,7 @@ void StateTrotting::run() {
|
|||
}
|
||||
|
||||
void StateTrotting::exit() {
|
||||
wave_generator_.status_ = WaveStatus::STANCE_ALL;
|
||||
wave_generator_.status_ = WaveStatus::SWING_ALL;
|
||||
}
|
||||
|
||||
FSMStateName StateTrotting::checkChange() {
|
||||
|
|
|
@ -11,8 +11,8 @@
|
|||
WaveGenerator::WaveGenerator() {
|
||||
phase_past_ << 0.5, 0.5, 0.5, 0.5;
|
||||
contact_past_.setZero();
|
||||
status_past_ = WaveStatus::STANCE_ALL;
|
||||
status_ = WaveStatus::STANCE_ALL;
|
||||
status_past_ = WaveStatus::SWING_ALL;
|
||||
status_ = WaveStatus::SWING_ALL;
|
||||
}
|
||||
|
||||
void WaveGenerator::init(const double period, const double st_ratio, const Vec4 &bias) {
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
<gazebo reference="${imu_name}">
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>500</update_rate>
|
||||
<update_rate>1000</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>imu</topic>
|
||||
<imu>
|
||||
|
@ -60,28 +60,28 @@
|
|||
</angular_velocity>
|
||||
<linear_acceleration>
|
||||
<x>
|
||||
<noise type="gaussian">
|
||||
<mean>0.0</mean>
|
||||
<stddev>1.7e-2</stddev>
|
||||
<bias_mean>0.1</bias_mean>
|
||||
<bias_stddev>0.001</bias_stddev>
|
||||
</noise>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>1.7e-2</stddev>-->
|
||||
<!-- <bias_mean>0.1</bias_mean>-->
|
||||
<!-- <bias_stddev>0.001</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</x>
|
||||
<y>
|
||||
<noise type="gaussian">
|
||||
<mean>0.0</mean>
|
||||
<stddev>1.7e-2</stddev>
|
||||
<bias_mean>0.1</bias_mean>
|
||||
<bias_stddev>0.001</bias_stddev>
|
||||
</noise>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>1.7e-2</stddev>-->
|
||||
<!-- <bias_mean>0.1</bias_mean>-->
|
||||
<!-- <bias_stddev>0.001</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</y>
|
||||
<z>
|
||||
<noise type="gaussian">
|
||||
<mean>0.0</mean>
|
||||
<stddev>1.7e-2</stddev>
|
||||
<bias_mean>0.1</bias_mean>
|
||||
<bias_stddev>0.001</bias_stddev>
|
||||
</noise>
|
||||
<!-- <noise type="gaussian">-->
|
||||
<!-- <mean>0.0</mean>-->
|
||||
<!-- <stddev>1.7e-2</stddev>-->
|
||||
<!-- <bias_mean>0.1</bias_mean>-->
|
||||
<!-- <bias_stddev>0.001</bias_stddev>-->
|
||||
<!-- </noise>-->
|
||||
</z>
|
||||
</linear_acceleration>
|
||||
</imu>
|
||||
|
|
Loading…
Reference in New Issue