APM:Libraries
AP_Devo_Telem.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 #pragma once
17 
18 #include <AP_HAL/AP_HAL.h>
19 #include <AP_AHRS/AP_AHRS.h>
21 
23 public:
24  //constructor
25  AP_DEVO_Telem(const AP_AHRS &ahrs);
26 
27  /* Do not allow copies */
28  AP_DEVO_Telem(const AP_DEVO_Telem &other) = delete;
29  AP_DEVO_Telem &operator=(const AP_DEVO_Telem&) = delete;
30 
31  // init - perform require initialisation including detecting which protocol to use
33 
34  // update flight control mode. The control mode is vehicle type specific
35  void update_control_mode(uint8_t mode)
36  {
37  _control_mode = mode;
38  }
39 
40 
41 private:
42  typedef struct PACKED {
43  uint8_t header;
44  int32_t lon;
45  int32_t lat;
46  int32_t alt;
47  int16_t speed;
48  int16_t temp;
49  int16_t volt;
50  uint8_t checksum8;
51  } DevoMPacket;
52 
53  uint32_t gpsDdToDmsFormat(float ddm);
54 
55  // tick - main call to send updates to transmitter (called by scheduler at 1kHz)
56  void tick(void);
57 
58  // send_frames - sends updates down telemetry link
59  void send_frames(uint8_t control_mode);
60 
62 
63  uint8_t _control_mode;
64 
65  const AP_AHRS &_ahrs; // reference to attitude estimate
66  AP_HAL::UARTDriver *_port; // UART used to send data to receiver
67  uint32_t _last_frame_ms;
68 
69 };
AP_HAL::UARTDriver * _port
Definition: AP_Devo_Telem.h:66
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
AP_DEVO_Telem & operator=(const AP_DEVO_Telem &)=delete
void init(const AP_SerialManager &serial_manager)
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
uint32_t gpsDdToDmsFormat(float ddm)
struct AP_DEVO_Telem::PACKED DevoMPacket
void update_control_mode(uint8_t mode)
Definition: AP_Devo_Telem.h:35
AP_DEVO_Telem(const AP_AHRS &ahrs)
uint32_t _last_frame_ms
Definition: AP_Devo_Telem.h:67
uint8_t header
0xAA for a valid packet
Definition: AP_Devo_Telem.h:43
void tick(void)
uint8_t _control_mode
Definition: AP_Devo_Telem.h:63
const AP_AHRS & _ahrs
Definition: AP_Devo_Telem.h:65
void send_frames(uint8_t control_mode)
DevoMPacket devoPacket
Definition: AP_Devo_Telem.h:61