mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
SITL: fixed ground accel for helis in FlightAxis
fixes landing detection
This commit is contained in:
parent
7c227ac96c
commit
79ffc28f68
@ -295,6 +295,13 @@ void FlightAxis::update(const struct sitl_input &input)
|
||||
accel_body(state.m_accelerationBodyAX_MPS2,
|
||||
state.m_accelerationBodyAY_MPS2,
|
||||
state.m_accelerationBodyAZ_MPS2);
|
||||
// accel on the ground is nasty in realflight, and prevents helicopter disarm
|
||||
if (state.m_isTouchingGround) {
|
||||
Vector3f accel_ef = (velocity_ef - last_velocity_ef) / dt_seconds;
|
||||
accel_ef.z -= GRAVITY_MSS;
|
||||
accel_body = dcm.transposed() * accel_ef;
|
||||
}
|
||||
|
||||
// limit to 16G to match pixhawk
|
||||
float a_limit = GRAVITY_MSS*16;
|
||||
accel_body.x = constrain_float(accel_body.x, -a_limit, a_limit);
|
||||
@ -337,6 +344,8 @@ void FlightAxis::update(const struct sitl_input &input)
|
||||
}
|
||||
|
||||
last_time_s = state.m_currentPhysicsTime_SEC;
|
||||
|
||||
last_velocity_ef = velocity_ef;
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
@ -166,6 +166,7 @@ private:
|
||||
uint64_t activation_frame_counter = 0;
|
||||
double last_frame_count_s = 0;
|
||||
Vector3f position_offset;
|
||||
Vector3f last_velocity_ef;
|
||||
|
||||
const char *controller_ip = "127.0.0.1";
|
||||
uint16_t controller_port = 18083;
|
||||
|
Loading…
Reference in New Issue
Block a user