SITL: Added comment to clarify IMU acceleration value
[ardupilot.git] / libraries / AP_Mount / AP_Mount_Params.h
blobccf42c1fe050c1a88b2143b0d93f0bb76425b773
1 #pragma once
3 #include <AP_Param/AP_Param.h>
4 #include <AP_Math/AP_Math.h>
6 class AP_Mount_Params {
8 public:
10 static const struct AP_Param::GroupInfo var_info[];
12 AP_Mount_Params(void);
14 /* Do not allow copies */
15 CLASS_NO_COPY(AP_Mount_Params);
17 AP_Int8 type; // mount type (see Mount::Type enum)
18 AP_Int8 default_mode; // default mode on startup and when control is returned from autopilot
19 AP_Int16 rc_rate_max; // Pilot rate control's maximum rate. Set to zero to use angle control
20 AP_Int16 roll_angle_min; // roll angle min in degrees
21 AP_Int16 roll_angle_max; // roll angle max in degrees
22 AP_Int16 pitch_angle_min; // pitch angle min in degrees
23 AP_Int16 pitch_angle_max; // pitch angle max in degrees
24 AP_Int16 yaw_angle_min; // yaw angle min in degrees
25 AP_Int16 yaw_angle_max; // yaw angle max in degrees
27 AP_Vector3f retract_angles; // retracted position in degrees. vector.x = roll vector.y = pitch, vector.z=yaw
28 AP_Vector3f neutral_angles; // neutral position in degrees. vector.x = roll vector.y = pitch, vector.z=yaw
30 AP_Float roll_stb_lead; // roll lead control gain (only used by servo backend)
31 AP_Float pitch_stb_lead; // pitch lead control gain (only used by servo backend)
32 AP_Int8 sysid_default; // target sysid for mount to follow
33 AP_Int32 dev_id; // Device id taking into account bus
34 AP_Int8 options; // mount options bitmask