Browse Source

AP_AHRS: add Roll90Yaw90 to parameter description

Thanks to Rainer Walther for spotting this
master
Randy Mackay 12 years ago
parent
commit
ded31582de
  1. 2
      libraries/AP_AHRS/AP_AHRS.cpp

2
libraries/AP_AHRS/AP_AHRS.cpp

@ -77,7 +77,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { @@ -77,7 +77,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
// @Param: ORIENTATION
// @DisplayName: Board Orientation
// @Description: Overall board orientation relative to the standard orientation for the board type. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. This option takes affect on next boot. After changing you will need to re-level your vehicle.
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw135,19:Roll270,20:Roll270Yaw45,21:Roll270Yaw90,22:Roll270Yaw136,23:Pitch90,24:Pitch270
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270
// @User: Advanced
AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0),

Loading…
Cancel
Save