APM:Libraries
AP_Mount_Servo.h
Go to the documentation of this file.
1 /*
2  Servo controlled mount backend class
3  */
4 #pragma once
5 
6 #include <AP_Math/AP_Math.h>
7 #include <AP_Common/AP_Common.h>
8 #include <AP_GPS/AP_GPS.h>
9 #include <AP_AHRS/AP_AHRS.h>
12 #include "AP_Mount_Backend.h"
13 
15 {
16 public:
17  // Constructor
18  AP_Mount_Servo(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance):
19  AP_Mount_Backend(frontend, state, instance),
20  _roll_idx(SRV_Channel::k_none),
21  _tilt_idx(SRV_Channel::k_none),
22  _pan_idx(SRV_Channel::k_none),
23  _open_idx(SRV_Channel::k_none),
25  {
26  // init to no axis being controlled
27  _flags.roll_control = false;
28  _flags.tilt_control = false;
29  _flags.pan_control = false;
30  }
31 
32  // init - performs any required initialisation for this instance
33  virtual void init(const AP_SerialManager& serial_manager);
34 
35  // update mount position - should be called periodically
36  virtual void update();
37 
38  // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
39  virtual bool has_pan_control() const { return _flags.pan_control; }
40 
41  // set_mode - sets mount's mode
42  virtual void set_mode(enum MAV_MOUNT_MODE mode);
43 
44  // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
45  virtual void status_msg(mavlink_channel_t chan);
46 
47 private:
48 
49  // flags structure
50  struct {
51  bool roll_control :1; // true if mount has roll control
52  bool tilt_control :1; // true if mount has tilt control
53  bool pan_control :1; // true if mount has pan control
54  } _flags;
55 
56  // check_servo_map - detects which axis we control (i.e. _flags) using the functions assigned to the servos in the SRV_Channel
57  // should be called periodically (i.e. 1hz or less)
58  void check_servo_map();
59 
60  // stabilize - stabilizes the mount relative to the Earth's frame
61  void stabilize();
62 
63  // closest_limit - returns closest angle to 'angle' taking into account limits. all angles are in degrees * 10
64  int16_t closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max);
65 
67  void move_servo(uint8_t rc, int16_t angle, int16_t angle_min, int16_t angle_max);
68 
69  // SRV_Channel - different id numbers are used depending upon the instance number
70  SRV_Channel::Aux_servo_function_t _roll_idx; // SRV_Channel mount roll function index
71  SRV_Channel::Aux_servo_function_t _tilt_idx; // SRV_Channel mount tilt function index
72  SRV_Channel::Aux_servo_function_t _pan_idx; // SRV_Channel mount pan function index
73  SRV_Channel::Aux_servo_function_t _open_idx; // SRV_Channel mount open function index
74 
75  Vector3f _angle_bf_output_deg; // final body frame output angle in degrees
76 
77  uint32_t _last_check_servo_map_ms; // system time of latest call to check_servo_map function
78 };
virtual void update()
SRV_Channel::Aux_servo_function_t _pan_idx
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
virtual void init(const AP_SerialManager &serial_manager)
static RC_Channel * rc
Definition: RC_Channel.cpp:17
virtual void status_msg(mavlink_channel_t chan)
AP_Mount_Servo(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
int16_t closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max)
uint32_t _last_check_servo_map_ms
SRV_Channel::Aux_servo_function_t _roll_idx
static int state
Definition: Util.cpp:20
Vector3f _angle_bf_output_deg
virtual bool has_pan_control() const
SRV_Channel::Aux_servo_function_t _open_idx
Common definitions and utility routines for the ArduPilot libraries.
struct AP_Mount_Servo::@135 _flags
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void move_servo(uint8_t rc, int16_t angle, int16_t angle_min, int16_t angle_max)
move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10 ...
virtual void set_mode(enum MAV_MOUNT_MODE mode)
SRV_Channel::Aux_servo_function_t _tilt_idx