123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include "AP_Mount.h"
- #include <RC_Channel/RC_Channel.h>
- class AP_Mount_Backend
- {
- public:
-
- AP_Mount_Backend(AP_Mount &frontend, AP_Mount::mount_state& state, uint8_t instance) :
- _frontend(frontend),
- _state(state),
- _instance(instance)
- {}
-
- virtual ~AP_Mount_Backend(void) {}
-
- virtual void init() = 0;
-
- virtual void update() = 0;
-
- virtual void update_fast() {}
-
- virtual bool has_pan_control() const = 0;
-
- virtual void set_mode(enum MAV_MOUNT_MODE mode) = 0;
-
- virtual void set_angle_targets(float roll, float tilt, float pan);
-
- virtual void set_roi_target(const struct Location &target_loc);
-
- virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode);
-
-
- void handle_mount_configure(const mavlink_mount_configure_t &msg);
-
- void handle_mount_control(const mavlink_mount_control_t &packet);
-
- virtual void send_mount_status(mavlink_channel_t chan) = 0;
-
- virtual void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) {}
-
- virtual void handle_param_value(const mavlink_message_t &msg) {}
-
- virtual void send_gimbal_report(const mavlink_channel_t chan) {}
- protected:
-
- void update_targets_from_rc();
-
- float angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max);
-
- void calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan = true);
-
- MAV_MOUNT_MODE get_mode(void) const { return _frontend.get_mode(_instance); }
- AP_Mount &_frontend;
- AP_Mount::mount_state &_state;
- uint8_t _instance;
- Vector3f _angle_ef_target_rad;
- private:
- void rate_input_rad(float &out, const RC_Channel *ch, float min, float max) const;
- };
|