APM:Libraries
AP_Devo_Telem.cpp
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  DEVO Telemetry library
18 */
19 
20 #define DEVOM_SYNC_BYTE 0xAA
21 
22 
23 #define AP_SERIALMANAGER_DEVO_TELEM_BAUD 38400
24 #define AP_SERIALMANAGER_DEVO_BUFSIZE_RX 0
25 #define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32
26 
27 #include "AP_Devo_Telem.h"
28 #include <AP_GPS/AP_GPS.h>
30 
31 extern const AP_HAL::HAL& hal;
32 
33 
34 //constructor
36  _ahrs(ahrs)
37 {
39 }
40 
41 // init - perform require initialisation including detecting which protocol to use
43 {
44  // check for DEVO_DPort
47  // initialise uart
49 
51  }
52 }
53 
54 
56 {
57  int32_t deg = (int32_t)ddm;
58  float mm = (ddm - deg) * 60.0f;
59 
60  mm = ((float)deg * 100.0f + mm) /100.0;
61 
62  if ((mm < -180.0f) || (mm > 180.0f)) {
63  mm = 0.0f;
64  }
65 
66  return mm * 1.0e7;
67 }
68 
69 
70 /*
71  send_frames - sends updates down telemetry link
72  should be called by main program at 1hz
73 */
74 
75 #define DEVO_SPEED_FACTOR 0.0194384f
76 
77 void AP_DEVO_Telem::send_frames(uint8_t control_mode)
78 {
79  // return immediately if not initialised
80  if (_port == nullptr) {
81  return;
82  }
83 
84  const AP_GPS &gps = AP::gps();
85  Location loc;
86 
87  if (_ahrs.get_position(loc)) {
90  devoPacket.speed = (int16_t)(gps.ground_speed() * DEVO_SPEED_FACTOR * 100.0f); // * 100 for cm
91 
92  /*
93  Note that this isn't actually barometric altitude, it is the
94  inertial nav estimate of altitude above home.
95  */
96  float alt;
98  devoPacket.alt = alt * -100.0f; // coordinates was in NED, so it needs to change sign. Protocol requires in cm!
99  } else {
100  devoPacket.lat = 0;
101  devoPacket.lon = 0;
102  devoPacket.speed = 0;
103  devoPacket.alt=0;
104  }
105 
106 
107 
108  devoPacket.volt = roundf(AP::battery().voltage() * 10.0f);
109  devoPacket.temp = control_mode; // Send mode as temperature
110 
111  devoPacket.checksum8 = 0; // Init Checksum with zero Byte
112 
113  uint8_t *b = (uint8_t *)&devoPacket;
114  for (uint8_t i = sizeof(devoPacket)-1; i !=0; i--) {
115  _port->write(b, 1);
116  devoPacket.checksum8 += *b++; // Add Checksum
117  }
119 }
120 
122 {
123  uint32_t now = AP_HAL::millis();
124 
125  if (now - _last_frame_ms > 1000) {
126  _last_frame_ms = now;
128  }
129 }
Definition: AP_GPS.h:48
AP_HAL::UARTDriver * _port
Definition: AP_Devo_Telem.h:66
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
void init(const AP_SerialManager &serial_manager)
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
virtual void begin(uint32_t baud)=0
virtual bool get_position(struct Location &loc) const =0
uint32_t gpsDdToDmsFormat(float ddm)
#define DEVO_SPEED_FACTOR
#define AP_SERIALMANAGER_DEVO_TELEM_BAUD
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
#define f(i)
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
virtual void set_flow_control(enum flow_control flow_control_setting)
Definition: UARTDriver.h:50
#define DEVOM_SYNC_BYTE
AP_DEVO_Telem(const AP_AHRS &ahrs)
AP_BattMonitor & battery()
#define AP_SERIALMANAGER_DEVO_BUFSIZE_RX
uint32_t _last_frame_ms
Definition: AP_Devo_Telem.h:67
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
virtual void register_io_process(AP_HAL::MemberProc)=0
float voltage
uint8_t header
0xAA for a valid packet
Definition: AP_Devo_Telem.h:43
void tick(void)
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
static AP_GPS gps
Definition: AHRS_Test.cpp:22
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)
virtual void get_relative_position_D_home(float &posD) const =0
#define AP_SERIALMANAGER_DEVO_BUFSIZE_TX
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
DevoMPacket devoPacket
Definition: AP_Devo_Telem.h:61