Browse Source

AP_AHRS: added attitude_reset() method for HIL_SENSORS

master
Andrew Tridgell 11 years ago
parent
commit
710d5119b5
  1. 6
      libraries/AP_AHRS/AP_AHRS_HIL.cpp

6
libraries/AP_AHRS/AP_AHRS_HIL.cpp

@ -36,3 +36,9 @@ AP_AHRS_HIL::setHil(float _roll, float _pitch, float _yaw, @@ -36,3 +36,9 @@ AP_AHRS_HIL::setHil(float _roll, float _pitch, float _yaw,
_dcm_matrix.from_euler(roll, pitch, yaw);
}
// reset the current attitude, used by HIL
void reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
{
// not implemented - use setHil()
}

Loading…
Cancel
Save