16 #define CMD_READ_PARAMS 'R'    17 #define CMD_WRITE_PARAMS 'W'    18 #define CMD_REALTIME_DATA 'D'    19 #define CMD_BOARD_INFO 'V'    20 #define CMD_CALIB_ACC 'A'    21 #define CMD_CALIB_GYRO 'g'    22 #define CMD_CALIB_EXT_GAIN 'G'    23 #define CMD_USE_DEFAULTS 'F'    24 #define CMD_CALIB_POLES 'P'    26 #define CMD_HELPER_DATA 'H'    27 #define CMD_CALIB_OFFSET 'O'    28 #define CMD_CALIB_BAT 'B'    29 #define CMD_MOTORS_ON 'M'    30 #define CMD_MOTORS_OFF 'm'    31 #define CMD_CONTROL 'C'    32 #define CMD_TRIGGER_PIN 'T'    33 #define CMD_EXECUTE_MENU 'E'    34 #define CMD_GET_ANGLES 'I'    35 #define CMD_CONFIRM 'C'    37 #define CMD_BOARD_INFO_3 20    38 #define CMD_READ_PARAMS_3 21    39 #define CMD_WRITE_PARAMS_3 22    40 #define CMD_REALTIME_DATA_3 23    41 #define CMD_SELECT_IMU_3 24    42 #define CMD_READ_PROFILE_NAMES 28    43 #define CMD_WRITE_PROFILE_NAMES 29    44 #define CMD_QUEUE_PARAMS_INFO_3 30    45 #define CMD_SET_PARAMS_3 31    46 #define CMD_SAVE_PARAMS_3 32    47 #define CMD_READ_PARAMS_EXT 33    48 #define CMD_WRITE_PARAMS_EXT 34    49 #define CMD_AUTO_PID 35    50 #define CMD_SERVO_OUT 36    53 #define AP_MOUNT_ALEXMOS_MODE_NO_CONTROL 0    54 #define AP_MOUNT_ALEXMOS_MODE_SPEED 1    55 #define AP_MOUNT_ALEXMOS_MODE_ANGLE 2    56 #define AP_MOUNT_ALEXMOS_MODE_SPEED_ANGLE 3    57 #define AP_MOUNT_ALEXMOS_MODE_RC 4    59 #define AP_MOUNT_ALEXMOS_SPEED 30 // degree/s2    61 #define VALUE_TO_DEGREE(d) ((float)((d * 720) >> 15))    62 #define DEGREE_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.02197265625f)))    63 #define DEGREE_PER_SEC_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.1220740379f)))    98     virtual void set_mode(
enum MAV_MOUNT_MODE mode) ;
   127     void send_command(uint8_t cmd, uint8_t* data, uint8_t size);
 
uint8_t _firmware_beta_version
 
static AP_SerialManager serial_manager
 
int16_t bat_threshold_alarm
 
int16_t roll_rc_max_angle
 
int8_t follow_offset_roll
 
AP_HAL::UARTDriver * _port
 
bool _gimbal_bat_monitoring
 
int16_t bat_threshold_motors
 
#define DEFINE_BYTE_ARRAY_METHODS
 
float _current_firmware_version
 
alexmos_angles_speed angle_speed
 
uint8_t i2c_internal_pullups
 
uint8_t booster_power_yaw
 
void send_command(uint8_t cmd, uint8_t *data, uint8_t size)
 
union PACKED AP_Mount_Alexmos::alexmos_parameters _buffer
 
A system for managing and storing variables that are of general interest to the system. 
 
virtual bool has_pan_control() const
 
union PACKED AP_Mount_Alexmos::alexmos_parameters _current_parameters
 
virtual void status_msg(mavlink_channel_t chan)
 
AP_Mount_Alexmos(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
 
int16_t pitch_rc_max_angle
 
virtual void set_mode(enum MAV_MOUNT_MODE mode)
 
void control_axis(const Vector3f &angle, bool targets_in_degrees)
 
uint16_t _firmware_version
 
void read_params(uint8_t profile_id)
 
uint8_t follow_speed_roll
 
uint8_t frame_angle_from_motors
 
bool _last_command_confirmed
 
uint8_t follow_roll_mix_start
 
uint8_t booster_power_pitch
 
bool get_realtimedata(Vector3f &angle)
 
AP_HAL::AnalogSource * chan
 
int16_t roll_rc_min_angle
 
uint8_t follow_roll_mix_range
 
int8_t follow_offset_pitch
 
uint8_t follow_speed_pitch
 
uint8_t booster_power_roll
 
int16_t pitch_rc_min_angle
 
DEFINE_BYTE_ARRAY_METHODS alexmos_version version
 
virtual void init(const AP_SerialManager &serial_manager)