mirror of https://github.com/ArduPilot/ardupilot
Copter: Set the gravitational acceleration value to the defined value
This commit is contained in:
parent
d7533843d5
commit
44a622ea7f
|
@ -627,8 +627,8 @@ void ModePosHold::get_wind_comp_lean_angles(float &roll_angle, float &pitch_angl
|
|||
wind_comp_timer = 0;
|
||||
|
||||
// convert earth frame desired accelerations to body frame roll and pitch lean angles
|
||||
roll_angle = atanf((-wind_comp_ef.x*ahrs.sin_yaw() + wind_comp_ef.y*ahrs.cos_yaw())/981.0f)*(18000.0f/M_PI);
|
||||
pitch_angle = atanf(-(wind_comp_ef.x*ahrs.cos_yaw() + wind_comp_ef.y*ahrs.sin_yaw())/981.0f)*(18000.0f/M_PI);
|
||||
roll_angle = atanf((-wind_comp_ef.x*ahrs.sin_yaw() + wind_comp_ef.y*ahrs.cos_yaw())/(GRAVITY_MSS*100))*(18000.0f/M_PI);
|
||||
pitch_angle = atanf(-(wind_comp_ef.x*ahrs.cos_yaw() + wind_comp_ef.y*ahrs.sin_yaw())/(GRAVITY_MSS*100))*(18000.0f/M_PI);
|
||||
}
|
||||
|
||||
// roll_controller_to_pilot_override - initialises transition from a controller submode (brake or loiter) to a pilot override on roll axis
|
||||
|
|
Loading…
Reference in New Issue