51 virtual void set_mode(
enum MAV_MOUNT_MODE mode) = 0;
60 virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode);
static AP_SerialManager serial_manager
virtual void handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
Vector3f _angle_ef_target_rad
virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode)
void update_targets_from_rc()
int32_t angle_input(RC_Channel *rc, int16_t angle_min, int16_t angle_max)
float angle_input_rad(RC_Channel *rc, int16_t angle_min, int16_t angle_max)
enum MAV_MOUNT_MODE get_mode() const
virtual void control_msg(mavlink_message_t *msg)
AP_Mount::mount_state & _state
virtual void set_mode(enum MAV_MOUNT_MODE mode)=0
virtual void status_msg(mavlink_channel_t chan)
virtual void set_angle_targets(float roll, float tilt, float pan)
virtual void send_gimbal_report(mavlink_channel_t chan)
virtual void update_fast()
Object managing one RC channel.
void calc_angle_to_location(const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
virtual void configure_msg(mavlink_message_t *msg)
virtual void set_roi_target(const struct Location &target_loc)
virtual ~AP_Mount_Backend(void)
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
virtual void handle_param_value(mavlink_message_t *msg)
virtual void init(const AP_SerialManager &serial_manager)=0
AP_Mount_Backend(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
virtual bool has_pan_control() const =0
MAV_MOUNT_MODE get_mode(void) const