APM:Libraries
AP_Mount_SToRM32_serial.h
Go to the documentation of this file.
1 /*
2  SToRM32 mount using serial protocol backend class
3  */
4 #pragma once
5 
6 #include <AP_HAL/AP_HAL.h>
7 #include <AP_AHRS/AP_AHRS.h>
8 
9 #include <AP_Math/AP_Math.h>
10 #include <AP_Common/AP_Common.h>
11 #include <AP_GPS/AP_GPS.h>
13 #include <RC_Channel/RC_Channel.h>
14 #include "AP_Mount_Backend.h"
15 
16 #define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second
17 
19 {
20 
21 public:
22  // Constructor
23  AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
24 
25  // init - performs any required initialisation for this instance
26  virtual void init(const AP_SerialManager& serial_manager);
27 
28  // update mount position - should be called periodically
29  virtual void update();
30 
31  // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
32  virtual bool has_pan_control() const;
33 
34  // set_mode - sets mount's mode
35  virtual void set_mode(enum MAV_MOUNT_MODE mode);
36 
37  // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
38  virtual void status_msg(mavlink_channel_t chan);
39 
40 private:
41 
42  // send_target_angles
43  void send_target_angles(float pitch_deg, float roll_deg, float yaw_deg);
44 
45  // send read data request
46  void get_angles();
47 
48  // read_incoming
49  void read_incoming();
50  void parse_reply();
51 
52  enum ReplyType {
56  };
57 
58  //void add_next_reply(ReplyType reply_type);
59  uint8_t get_reply_size(ReplyType reply_type);
60  bool can_send(bool with_control);
61 
63  uint16_t state;
64  uint16_t status;
65  uint16_t status2;
66 
67  uint16_t i2c_errors;
68  uint16_t lipo_voltage;
69  uint16_t systicks;
70  uint16_t cycle_time;
71 
72  int16_t imu1_gx;
73  int16_t imu1_gy;
74  int16_t imu1_gz;
75 
76  int16_t imu1_ax;
77  int16_t imu1_ay;
78  int16_t imu1_az;
79 
80  int16_t ahrs_x;
81  int16_t ahrs_y;
82  int16_t ahrs_z;
83 
84  int16_t imu1_pitch;
85  int16_t imu1_roll;
86  int16_t imu1_yaw;
87 
88  int16_t cpid_pitch;
89  int16_t cpid_roll;
90  int16_t cpid_yaw;
91 
92  uint16_t input_pitch;
93  uint16_t input_roll;
94  uint16_t input_yaw;
95 
96  int16_t imu2_pitch;
97  int16_t imu2_roll;
98  int16_t imu2_yaw;
99 
100  int16_t mag2_yaw;
101  int16_t mag2_pitch;
102 
104 
106 
107  uint16_t crc;
108  uint8_t magic;
109  };
110 
112  uint8_t byte1;
113  uint8_t byte2;
114  uint8_t byte3;
115  uint8_t data;
116  uint16_t crc;
117  };
118 
120  uint8_t byte1;
121  uint8_t byte2;
122  uint8_t byte3;
123  float pitch;
124  float roll;
125  float yaw;
126  uint8_t flags;
127  uint8_t type;
128  uint16_t crc;
129  };
130 
131 
132  // internal variables
134 
135  bool _initialised; // true once the driver has been initialised
136  uint32_t _last_send; // system time of last do_mount_control sent to gimbal
137 
138  uint8_t _reply_length;
139  uint8_t _reply_counter;
141 
142 
147  } _buffer;
148 
149  // keep the last _current_angle values
151 };
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
virtual void init(const AP_SerialManager &serial_manager)
union PACKED AP_Mount_SToRM32_serial::SToRM32_reply _buffer
#define DEFINE_BYTE_ARRAY_METHODS
Definition: AP_Common.h:58
uint8_t get_reply_size(ReplyType reply_type)
bool can_send(bool with_control)
void send_target_angles(float pitch_deg, float roll_deg, float yaw_deg)
virtual void status_msg(mavlink_channel_t chan)
RC_Channel manager, with EEPROM-backed storage of constants.
static int state
Definition: Util.cpp:20
virtual bool has_pan_control() const
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
DEFINE_BYTE_ARRAY_METHODS SToRM32_reply_data_struct data
#define PACKED
Definition: AP_Common.h:28
AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
virtual void set_mode(enum MAV_MOUNT_MODE mode)