APM:Libraries
AP_Mount_Backend.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  Mount driver backend class. Each supported mount type
18  needs to have an object derived from this class.
19  */
20 #pragma once
21 
22 #include <AP_Common/AP_Common.h>
23 #include "AP_Mount.h"
24 
26 {
27 public:
28  // Constructor
29  AP_Mount_Backend(AP_Mount &frontend, AP_Mount::mount_state& state, uint8_t instance) :
30  _frontend(frontend),
31  _state(state),
32  _instance(instance)
33  {}
34 
35  // Virtual destructor
36  virtual ~AP_Mount_Backend(void) {}
37 
38  // init - performs any required initialisation for this instance
39  virtual void init(const AP_SerialManager& serial_manager) = 0;
40 
41  // update mount position - should be called periodically
42  virtual void update() = 0;
43 
44  // used for gimbals that need to read INS data at full rate
45  virtual void update_fast() {}
46 
47  // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
48  virtual bool has_pan_control() const = 0;
49 
50  // set_mode - sets mount's mode
51  virtual void set_mode(enum MAV_MOUNT_MODE mode) = 0;
52 
53  // set_angle_targets - sets angle targets in degrees
54  virtual void set_angle_targets(float roll, float tilt, float pan);
55 
56  // set_roi_target - sets target location that mount should attempt to point towards
57  virtual void set_roi_target(const struct Location &target_loc);
58 
59  // control - control the mount
60  virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode);
61 
62  // configure_msg - process MOUNT_CONFIGURE messages received from GCS
63  virtual void configure_msg(mavlink_message_t* msg);
64 
65  // control_msg - process MOUNT_CONTROL messages received from GCS
66  virtual void control_msg(mavlink_message_t* msg);
67 
68  // status_msg - called to allow mounts to send their status to GCS via MAVLink
69  virtual void status_msg(mavlink_channel_t chan) {}
70 
71  // handle a GIMBAL_REPORT message
72  virtual void handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg) {}
73 
74  // handle a PARAM_VALUE message
75  virtual void handle_param_value(mavlink_message_t *msg) {}
76 
77  // send a GIMBAL_REPORT message to the GCS
78  virtual void send_gimbal_report(mavlink_channel_t chan) {}
79 
80 protected:
81 
82  // update_targets_from_rc - updates angle targets (i.e. _angle_ef_target_rad) using input from receiver
84 
85  // angle_input, angle_input_rad - convert RC input into an earth-frame target angle
86  int32_t angle_input(RC_Channel* rc, int16_t angle_min, int16_t angle_max);
87  float angle_input_rad(RC_Channel* rc, int16_t angle_min, int16_t angle_max);
88 
89  // calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target
90  void calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan = true);
91 
92  // get the mount mode from frontend
93  MAV_MOUNT_MODE get_mode(void) const { return _frontend.get_mode(_instance); }
94 
95  AP_Mount &_frontend; // reference to the front end which holds parameters
96  AP_Mount::mount_state &_state; // references to the parameters and state for this backend
97  uint8_t _instance; // this instance's number
98  Vector3f _angle_ef_target_rad; // desired earth-frame roll, tilt and vehicle-relative pan angles in radians
99 };
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
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)
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
Definition: AP_Mount.h:93
virtual void control_msg(mavlink_message_t *msg)
static RC_Channel * rc
Definition: RC_Channel.cpp:17
AP_Mount::mount_state & _state
virtual void set_mode(enum MAV_MOUNT_MODE mode)=0
virtual void update()=0
virtual void status_msg(mavlink_channel_t chan)
virtual void set_angle_targets(float roll, float tilt, float pan)
AP_Mount & _frontend
virtual void send_gimbal_report(mavlink_channel_t chan)
virtual void update_fast()
Object managing one RC channel.
Definition: RC_Channel.h:15
void calc_angle_to_location(const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
static int state
Definition: Util.cpp:20
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
Definition: AnalogIn.cpp:8
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