LP-500 HoTT Bridge Module ported from TauLabs
[librepilot.git] / flight / modules / UAVOHottBridge / uavohottbridge.c
blob56a442e36766a043400cd3face410c4b10235a68
1 /**
2 ******************************************************************************
3 * @addtogroup OpenPilotModules OpenPilot Modules
4 * @{
5 * @addtogroup UAVOHoTTBridge UAVO to HoTT Bridge Telemetry Module
6 * @{
8 * @file uavohottridge.c
9 * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
10 * Tau Labs, http://taulabs.org, Copyright (C) 2013-2014
11 * @brief sends telemery data on HoTT request
13 * @see The GNU Public License (GPL) Version 3
15 *****************************************************************************/
17 * This program is free software; you can redistribute it and/or modify
18 * it under the terms of the GNU General Public License as published by
19 * the Free Software Foundation; either version 3 of the License, or
20 * (at your option) any later version.
22 * This program is distributed in the hope that it will be useful, but
23 * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
24 * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
25 * for more details.
27 * You should have received a copy of the GNU General Public License along
28 * with this program; if not, write to the Free Software Foundation, Inc.,
29 * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
31 * Additional note on redistribution: The copyright and license notices above
32 * must be maintained in each individual source file that is a derivative work
33 * of this source file; otherwise redistribution is prohibited.
36 #include "openpilot.h"
37 #include "hwsettings.h"
38 #include "taskinfo.h"
39 #include "callbackinfo.h"
40 #include "hottbridgesettings.h"
41 #include "attitudestate.h"
42 #include "barosensor.h"
43 #include "flightbatterystate.h"
44 #include "flightstatus.h"
45 #include "gyrosensor.h"
46 #include "gpspositionsensor.h"
47 #include "gpstime.h"
48 #include "homelocation.h"
49 #include "positionstate.h"
50 #include "systemalarms.h"
51 #include "velocitystate.h"
52 #include "hottbridgestatus.h"
53 #include "hottbridgesettings.h"
54 #include "objectpersistence.h"
55 #include "pios_sensors.h"
56 #include "uavohottbridge.h"
58 #if defined(PIOS_INCLUDE_HOTT_BRIDGE)
60 #if defined(PIOS_HoTT_STACK_SIZE)
61 #define STACK_SIZE_BYTES PIOS_HoTT_STACK_SIZE
62 #else
63 #define STACK_SIZE_BYTES 2048
64 #endif
65 #define TASK_PRIORITY CALLBACK_TASK_AUXILIARY
67 static bool module_enabled = false;
69 // Private variables
70 static bool module_enabled;
71 static struct telemetrydata *telestate;
72 static HoTTBridgeStatusData status;
74 // Private functions
75 static void uavoHoTTBridgeTask(void *parameters);
76 static uint16_t build_VARIO_message(struct hott_vario_message *msg);
77 static uint16_t build_GPS_message(struct hott_gps_message *msg);
78 static uint16_t build_GAM_message(struct hott_gam_message *msg);
79 static uint16_t build_EAM_message(struct hott_eam_message *msg);
80 static uint16_t build_ESC_message(struct hott_esc_message *msg);
81 static uint16_t build_TEXT_message(struct hott_text_message *msg);
82 static uint8_t calc_checksum(uint8_t *data, uint16_t size);
83 static uint8_t generate_warning();
84 static void update_telemetrydata();
85 static void convert_long2gps(int32_t value, uint8_t *dir, uword_t *min, uword_t *sec);
86 static uint8_t scale_float2uint8(float value, float scale, float offset);
87 static int8_t scale_float2int8(float value, float scale, float offset);
88 static uword_t scale_float2uword(float value, float scale, float offset);
90 /**
91 * Module start routine automatically called after initialization routine
92 * @return 0 when was successful
94 static int32_t uavoHoTTBridgeStart(void)
96 status.TxPackets = 0;
97 status.RxPackets = 0;
98 status.TxFail = 0;
99 status.RxFail = 0;
102 // Start task
103 if (module_enabled) {
104 xTaskHandle taskHandle;
106 xTaskCreate(uavoHoTTBridgeTask, "uavoHoTTBridge", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
107 PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_UAVOHOTTBRIDGE, taskHandle);
110 return 0;
114 * Module initialization routine
115 * @return 0 when initialization was successful
117 static int32_t uavoHoTTBridgeInitialize(void)
119 if (PIOS_COM_HOTT) {
120 module_enabled = true;
121 // HoTT telemetry baudrate is fixed to 19200
123 PIOS_COM_ChangeBaud(PIOS_COM_HOTT, 19200);
124 PIOS_COM_SetHalfDuplex(PIOS_COM_HOTT, true);
125 HoTTBridgeSettingsInitialize();
126 HoTTBridgeStatusInitialize();
128 // allocate memory for telemetry data
129 telestate = (struct telemetrydata *)pios_malloc(sizeof(*telestate));
131 if (telestate == NULL) {
132 // there is not enough free memory. the module could not run.
133 module_enabled = false;
134 return -1;
136 } else {
137 module_enabled = false;
139 return 0;
141 MODULE_INITCALL(uavoHoTTBridgeInitialize, uavoHoTTBridgeStart);
144 * Main task. It does not return.
146 static void uavoHoTTBridgeTask(__attribute__((unused)) void *parameters)
148 uint8_t rx_buffer[2];
149 uint8_t tx_buffer[HOTT_MAX_MESSAGE_LENGTH];
150 uint16_t message_size;
152 // clear all state values
153 memset(telestate, 0, sizeof(*telestate));
155 // initialize timer variables
156 portTickType lastSysTime = xTaskGetTickCount();
157 // idle delay between telemetry request and answer
158 uint32_t idledelay = IDLE_TIME;
159 // data delay between transmitted bytes
160 uint32_t datadelay = DATA_TIME;
162 // work on hott telemetry. endless loop.
163 while (1) {
164 // clear message size on every loop before processing
165 message_size = 0;
167 // shift receiver buffer. make room for one byte.
168 rx_buffer[1] = rx_buffer[0];
170 // wait for a byte of telemetry request in data delay interval
171 while (PIOS_COM_ReceiveBuffer(PIOS_COM_HOTT, rx_buffer, 1, 0) == 0) {
172 vTaskDelayUntil(&lastSysTime, datadelay / portTICK_RATE_MS);
174 // set start trigger point
175 lastSysTime = xTaskGetTickCount();
177 // examine received data stream
178 if (rx_buffer[1] == HOTT_BINARY_ID) {
179 // first received byte looks like a binary request. check second received byte for a sensor id.
180 switch (rx_buffer[0]) {
181 case HOTT_VARIO_ID:
182 message_size = build_VARIO_message((struct hott_vario_message *)tx_buffer);
183 break;
184 case HOTT_GPS_ID:
185 message_size = build_GPS_message((struct hott_gps_message *)tx_buffer);
186 break;
187 case HOTT_GAM_ID:
188 message_size = build_GAM_message((struct hott_gam_message *)tx_buffer);
189 break;
190 case HOTT_EAM_ID:
191 message_size = build_EAM_message((struct hott_eam_message *)tx_buffer);
192 break;
193 case HOTT_ESC_ID:
194 message_size = build_ESC_message((struct hott_esc_message *)tx_buffer);
195 break;
196 default:
197 message_size = 0;
199 } else if (rx_buffer[1] == HOTT_TEXT_ID) {
200 // first received byte looks like a text request. check second received byte for a valid button.
201 switch (rx_buffer[0]) {
202 case HOTT_BUTTON_DEC:
203 case HOTT_BUTTON_INC:
204 case HOTT_BUTTON_SET:
205 case HOTT_BUTTON_NIL:
206 case HOTT_BUTTON_NEXT:
207 case HOTT_BUTTON_PREV:
208 message_size = build_TEXT_message((struct hott_text_message *)tx_buffer);
209 break;
210 default:
211 message_size = 0;
215 // check if a message is in the transmit buffer.
216 if (message_size > 0) {
217 status.RxPackets++;
219 // check idle line before transmit. pause, then check receiver buffer
220 vTaskDelayUntil(&lastSysTime, idledelay / portTICK_RATE_MS);
222 if (PIOS_COM_ReceiveBuffer(PIOS_COM_HOTT, rx_buffer, 1, 0) == 0) {
223 // nothing received means idle line. ready to transmit the requested message
224 for (int i = 0; i < message_size; i++) {
225 // send message content with pause between each byte
226 PIOS_COM_SendCharNonBlocking(PIOS_COM_HOTT, tx_buffer[i]);
227 // grab possible incoming loopback data and throw it away
228 PIOS_COM_ReceiveBuffer(PIOS_COM_HOTT, rx_buffer, sizeof(rx_buffer), 0);
229 vTaskDelayUntil(&lastSysTime, datadelay / portTICK_RATE_MS);
231 status.TxPackets++;
234 // after transmitting the message, any loopback data needs to be cleaned up.
235 vTaskDelayUntil(&lastSysTime, idledelay / portTICK_RATE_MS);
236 PIOS_COM_ReceiveBuffer(PIOS_COM_HOTT, tx_buffer, message_size, 0);
237 } else {
238 status.RxFail++;
240 HoTTBridgeStatusSet(&status);
246 * Build requested answer messages.
247 * \return value sets message size
249 uint16_t build_VARIO_message(struct hott_vario_message *msg)
251 update_telemetrydata();
253 if (telestate->Settings.Sensor.VARIO == HOTTBRIDGESETTINGS_SENSOR_DISABLED) {
254 return 0;
257 // clear message buffer
258 memset(msg, 0, sizeof(*msg));
260 // message header
261 msg->start = HOTT_START;
262 msg->stop = HOTT_STOP;
263 msg->sensor_id = HOTT_VARIO_ID;
264 msg->warning = generate_warning();
265 msg->sensor_text_id = HOTT_VARIO_TEXT_ID;
267 // alarm inverse bits. invert display areas on limits
268 msg->alarm_inverse |= (telestate->Settings.Limit.MinHeight > telestate->altitude) ? VARIO_INVERT_ALT : 0;
269 msg->alarm_inverse |= (telestate->Settings.Limit.MaxHeight < telestate->altitude) ? VARIO_INVERT_ALT : 0;
270 msg->alarm_inverse |= (telestate->Settings.Limit.MaxHeight < telestate->altitude) ? VARIO_INVERT_MAX : 0;
271 msg->alarm_inverse |= (telestate->Settings.Limit.MinHeight > telestate->altitude) ? VARIO_INVERT_MIN : 0;
272 msg->alarm_inverse |= (telestate->Settings.Limit.NegDifference1 > telestate->climbrate1s) ? VARIO_INVERT_CR1S : 0;
273 msg->alarm_inverse |= (telestate->Settings.Limit.PosDifference1 < telestate->climbrate1s) ? VARIO_INVERT_CR1S : 0;
274 msg->alarm_inverse |= (telestate->Settings.Limit.NegDifference2 > telestate->climbrate3s) ? VARIO_INVERT_CR3S : 0;
275 msg->alarm_inverse |= (telestate->Settings.Limit.PosDifference2 < telestate->climbrate3s) ? VARIO_INVERT_CR3S : 0;
276 msg->alarm_inverse |= (telestate->Settings.Limit.NegDifference2 > telestate->climbrate10s) ? VARIO_INVERT_CR10S : 0;
277 msg->alarm_inverse |= (telestate->Settings.Limit.PosDifference2 < telestate->climbrate10s) ? VARIO_INVERT_CR10S : 0;
279 // altitude relative to ground
280 msg->altitude = scale_float2uword(telestate->altitude, 1, OFFSET_ALTITUDE);
281 msg->min_altitude = scale_float2uword(telestate->min_altitude, 1, OFFSET_ALTITUDE);
282 msg->max_altitude = scale_float2uword(telestate->max_altitude, 1, OFFSET_ALTITUDE);
284 // climbrate
285 msg->climbrate = scale_float2uword(telestate->climbrate1s, M_TO_CM, OFFSET_CLIMBRATE);
286 msg->climbrate3s = scale_float2uword(telestate->climbrate3s, M_TO_CM, OFFSET_CLIMBRATE);
287 msg->climbrate10s = scale_float2uword(telestate->climbrate10s, M_TO_CM, OFFSET_CLIMBRATE);
289 // compass
290 msg->compass = scale_float2int8(telestate->Attitude.Yaw, DEG_TO_UINT, 0);
292 // statusline
293 memcpy(msg->ascii, telestate->statusline, sizeof(msg->ascii));
295 // free display characters
296 msg->ascii1 = 0;
297 msg->ascii2 = 0;
298 msg->ascii3 = 0;
300 msg->checksum = calc_checksum((uint8_t *)msg, sizeof(*msg));
301 return sizeof(*msg);
304 uint16_t build_GPS_message(struct hott_gps_message *msg)
306 update_telemetrydata();
308 if (telestate->Settings.Sensor.GPS == HOTTBRIDGESETTINGS_SENSOR_DISABLED) {
309 return 0;
312 // clear message buffer
313 memset(msg, 0, sizeof(*msg));
315 // message header
316 msg->start = HOTT_START;
317 msg->stop = HOTT_STOP;
318 msg->sensor_id = HOTT_GPS_ID;
319 msg->warning = generate_warning();
320 msg->sensor_text_id = HOTT_GPS_TEXT_ID;
322 // alarm inverse bits. invert display areas on limits
323 msg->alarm_inverse1 |= (telestate->Settings.Limit.MaxDistance < telestate->homedistance) ? GPS_INVERT_HDIST : 0;
324 msg->alarm_inverse1 |= (telestate->Settings.Limit.MinSpeed > telestate->GPS.Groundspeed) ? GPS_INVERT_SPEED : 0;
325 msg->alarm_inverse1 |= (telestate->Settings.Limit.MaxSpeed < telestate->GPS.Groundspeed) ? GPS_INVERT_SPEED : 0;
326 msg->alarm_inverse1 |= (telestate->Settings.Limit.MinHeight > telestate->altitude) ? GPS_INVERT_ALT : 0;
327 msg->alarm_inverse1 |= (telestate->Settings.Limit.MaxHeight < telestate->altitude) ? GPS_INVERT_ALT : 0;
328 msg->alarm_inverse1 |= (telestate->Settings.Limit.NegDifference1 > telestate->climbrate1s) ? GPS_INVERT_CR1S : 0;
329 msg->alarm_inverse1 |= (telestate->Settings.Limit.PosDifference1 < telestate->climbrate1s) ? GPS_INVERT_CR1S : 0;
330 msg->alarm_inverse1 |= (telestate->Settings.Limit.NegDifference2 > telestate->climbrate3s) ? GPS_INVERT_CR3S : 0;
331 msg->alarm_inverse1 |= (telestate->Settings.Limit.PosDifference2 < telestate->climbrate3s) ? GPS_INVERT_CR3S : 0;
332 msg->alarm_inverse2 |= (telestate->SysAlarms.Alarm.GPS != SYSTEMALARMS_ALARM_OK) ? GPS_INVERT2_POS : 0;
334 // gps direction, groundspeed and postition
335 msg->flight_direction = scale_float2uint8(telestate->GPS.Heading, DEG_TO_UINT, 0);
336 msg->gps_speed = scale_float2uword(telestate->GPS.Groundspeed, MS_TO_KMH, 0);
337 convert_long2gps(telestate->GPS.Latitude, &msg->latitude_ns, &msg->latitude_min, &msg->latitude_sec);
338 convert_long2gps(telestate->GPS.Longitude, &msg->longitude_ew, &msg->longitude_min, &msg->longitude_sec);
340 // homelocation distance, course and state
341 msg->distance = scale_float2uword(telestate->homedistance, 1, 0);
342 msg->home_direction = scale_float2uint8(telestate->homecourse, DEG_TO_UINT, 0);
343 msg->ascii5 = (telestate->Home.Set ? 'H' : '-');
345 // altitude relative to ground and climb rate
346 msg->altitude = scale_float2uword(telestate->altitude, 1, OFFSET_ALTITUDE);
347 msg->climbrate = scale_float2uword(telestate->climbrate1s, M_TO_CM, OFFSET_CLIMBRATE);
348 msg->climbrate3s = scale_float2uint8(telestate->climbrate3s, 1, OFFSET_CLIMBRATE3S);
350 // number of satellites,gps fix and state
351 msg->gps_num_sat = telestate->GPS.Satellites;
352 switch (telestate->GPS.Status) {
353 case GPSPOSITIONSENSOR_STATUS_FIX2D:
354 msg->gps_fix_char = '2';
355 break;
356 case GPSPOSITIONSENSOR_STATUS_FIX3D:
357 msg->gps_fix_char = '3';
358 break;
359 default:
360 msg->gps_fix_char = 0;
362 switch (telestate->SysAlarms.Alarm.GPS) {
363 case SYSTEMALARMS_ALARM_UNINITIALISED:
364 msg->ascii6 = 0;
365 // if there is no gps, show compass flight direction
366 msg->flight_direction = scale_float2int8((telestate->Attitude.Yaw > 0) ? telestate->Attitude.Yaw : 360 + telestate->Attitude.Yaw, DEG_TO_UINT, 0);
367 break;
368 case SYSTEMALARMS_ALARM_OK:
369 msg->ascii6 = '.';
370 break;
371 case SYSTEMALARMS_ALARM_WARNING:
372 msg->ascii6 = '?';
373 break;
374 case SYSTEMALARMS_ALARM_ERROR:
375 case SYSTEMALARMS_ALARM_CRITICAL:
376 msg->ascii6 = '!';
377 break;
378 default:
379 msg->ascii6 = 0;
382 // model angles
383 msg->angle_roll = scale_float2int8(telestate->Attitude.Roll, DEG_TO_UINT, 0);
384 msg->angle_nick = scale_float2int8(telestate->Attitude.Pitch, DEG_TO_UINT, 0);
385 msg->angle_compass = scale_float2int8(telestate->Attitude.Yaw, DEG_TO_UINT, 0);
387 // gps time
388 msg->gps_hour = telestate->GPStime.Hour;
389 msg->gps_min = telestate->GPStime.Minute;
390 msg->gps_sec = telestate->GPStime.Second;
391 msg->gps_msec = 0;
393 // gps MSL (NN) altitude MSL
394 msg->msl = scale_float2uword(telestate->GPS.Altitude, 1, 0);
396 // free display chararacter
397 msg->ascii4 = 0;
399 msg->checksum = calc_checksum((uint8_t *)msg, sizeof(*msg));
400 return sizeof(*msg);
403 uint16_t build_GAM_message(struct hott_gam_message *msg)
405 update_telemetrydata();
407 if (telestate->Settings.Sensor.GAM == HOTTBRIDGESETTINGS_SENSOR_DISABLED) {
408 return 0;
411 // clear message buffer
412 memset(msg, 0, sizeof(*msg));
414 // message header
415 msg->start = HOTT_START;
416 msg->stop = HOTT_STOP;
417 msg->sensor_id = HOTT_GAM_ID;
418 msg->warning = generate_warning();
419 msg->sensor_text_id = HOTT_GAM_TEXT_ID;
421 // alarm inverse bits. invert display areas on limits
422 msg->alarm_inverse2 |= (telestate->Settings.Limit.MaxCurrent < telestate->Battery.Current) ? GAM_INVERT2_CURRENT : 0;
423 msg->alarm_inverse2 |= (telestate->Settings.Limit.MinPowerVoltage > telestate->Battery.Voltage) ? GAM_INVERT2_VOLTAGE : 0;
424 msg->alarm_inverse2 |= (telestate->Settings.Limit.MaxPowerVoltage < telestate->Battery.Voltage) ? GAM_INVERT2_VOLTAGE : 0;
425 msg->alarm_inverse2 |= (telestate->Settings.Limit.MinHeight > telestate->altitude) ? GAM_INVERT2_ALT : 0;
426 msg->alarm_inverse2 |= (telestate->Settings.Limit.MaxHeight < telestate->altitude) ? GAM_INVERT2_ALT : 0;
427 msg->alarm_inverse2 |= (telestate->Settings.Limit.NegDifference1 > telestate->climbrate1s) ? GAM_INVERT2_CR1S : 0;
428 msg->alarm_inverse2 |= (telestate->Settings.Limit.PosDifference1 < telestate->climbrate1s) ? GAM_INVERT2_CR1S : 0;
429 msg->alarm_inverse2 |= (telestate->Settings.Limit.NegDifference2 > telestate->climbrate3s) ? GAM_INVERT2_CR3S : 0;
430 msg->alarm_inverse2 |= (telestate->Settings.Limit.PosDifference2 < telestate->climbrate3s) ? GAM_INVERT2_CR3S : 0;
432 // temperatures
433 msg->temperature1 = scale_float2uint8(telestate->Gyro.temperature, 1, OFFSET_TEMPERATURE);
434 msg->temperature2 = scale_float2uint8(telestate->Baro.Temperature, 1, OFFSET_TEMPERATURE);
436 // altitude
437 msg->altitude = scale_float2uword(telestate->altitude, 1, OFFSET_ALTITUDE);
439 // climbrate
440 msg->climbrate = scale_float2uword(telestate->climbrate1s, M_TO_CM, OFFSET_CLIMBRATE);
441 msg->climbrate3s = scale_float2uint8(telestate->climbrate3s, 1, OFFSET_CLIMBRATE3S);
443 // main battery
444 float voltage = (telestate->Battery.Voltage > 0) ? telestate->Battery.Voltage : 0;
445 float current = (telestate->Battery.Current > 0) ? telestate->Battery.Current : 0;
446 float energy = (telestate->Battery.ConsumedEnergy > 0) ? telestate->Battery.ConsumedEnergy : 0;
447 msg->voltage = scale_float2uword(voltage, 10, 0);
448 msg->current = scale_float2uword(current, 10, 0);
449 msg->capacity = scale_float2uword(energy, 0.1f, 0);
451 // pressure kPa to 0.1Bar
452 msg->pressure = scale_float2uint8(telestate->Baro.Pressure, 0.1f, 0);
454 msg->checksum = calc_checksum((uint8_t *)msg, sizeof(*msg));
455 return sizeof(*msg);
458 uint16_t build_EAM_message(struct hott_eam_message *msg)
460 update_telemetrydata();
462 if (telestate->Settings.Sensor.EAM == HOTTBRIDGESETTINGS_SENSOR_DISABLED) {
463 return 0;
466 // clear message buffer
467 memset(msg, 0, sizeof(*msg));
469 // message header
470 msg->start = HOTT_START;
471 msg->stop = HOTT_STOP;
472 msg->sensor_id = HOTT_EAM_ID;
473 msg->warning = generate_warning();
474 msg->sensor_text_id = HOTT_EAM_TEXT_ID;
476 // alarm inverse bits. invert display areas on limits
477 msg->alarm_inverse1 |= (telestate->Settings.Limit.MaxUsedCapacity < telestate->Battery.ConsumedEnergy) ? EAM_INVERT_CAPACITY : 0;
478 msg->alarm_inverse1 |= (telestate->Settings.Limit.MaxCurrent < telestate->Battery.Current) ? EAM_INVERT_CURRENT : 0;
479 msg->alarm_inverse1 |= (telestate->Settings.Limit.MinPowerVoltage > telestate->Battery.Voltage) ? EAM_INVERT_VOLTAGE : 0;
480 msg->alarm_inverse1 |= (telestate->Settings.Limit.MaxPowerVoltage < telestate->Battery.Voltage) ? EAM_INVERT_VOLTAGE : 0;
481 msg->alarm_inverse2 |= (telestate->Settings.Limit.MinHeight > telestate->altitude) ? EAM_INVERT2_ALT : 0;
482 msg->alarm_inverse2 |= (telestate->Settings.Limit.MaxHeight < telestate->altitude) ? EAM_INVERT2_ALT : 0;
483 msg->alarm_inverse2 |= (telestate->Settings.Limit.NegDifference1 > telestate->climbrate1s) ? EAM_INVERT2_CR1S : 0;
484 msg->alarm_inverse2 |= (telestate->Settings.Limit.PosDifference1 < telestate->climbrate1s) ? EAM_INVERT2_CR1S : 0;
485 msg->alarm_inverse2 |= (telestate->Settings.Limit.NegDifference2 > telestate->climbrate3s) ? EAM_INVERT2_CR3S : 0;
486 msg->alarm_inverse2 |= (telestate->Settings.Limit.PosDifference2 < telestate->climbrate3s) ? EAM_INVERT2_CR3S : 0;
488 // main battery
489 float voltage = (telestate->Battery.Voltage > 0) ? telestate->Battery.Voltage : 0;
490 float current = (telestate->Battery.Current > 0) ? telestate->Battery.Current : 0;
491 float energy = (telestate->Battery.ConsumedEnergy > 0) ? telestate->Battery.ConsumedEnergy : 0;
492 msg->voltage = scale_float2uword(voltage, 10, 0);
493 msg->current = scale_float2uword(current, 10, 0);
494 msg->capacity = scale_float2uword(energy, 0.1f, 0);
496 // temperatures
497 msg->temperature1 = scale_float2uint8(telestate->Gyro.temperature, 1, OFFSET_TEMPERATURE);
498 msg->temperature2 = scale_float2uint8(telestate->Baro.Temperature, 1, OFFSET_TEMPERATURE);
500 // altitude
501 msg->altitude = scale_float2uword(telestate->altitude, 1, OFFSET_ALTITUDE);
503 // climbrate
504 msg->climbrate = scale_float2uword(telestate->climbrate1s, M_TO_CM, OFFSET_CLIMBRATE);
505 msg->climbrate3s = scale_float2uint8(telestate->climbrate3s, 1, OFFSET_CLIMBRATE3S);
507 // flight time
508 float flighttime = (telestate->Battery.EstimatedFlightTime <= 5999) ? telestate->Battery.EstimatedFlightTime : 5999;
509 msg->electric_min = flighttime / 60;
510 msg->electric_sec = flighttime - 60 * msg->electric_min;
512 msg->checksum = calc_checksum((uint8_t *)msg, sizeof(*msg));
513 return sizeof(*msg);
516 uint16_t build_ESC_message(struct hott_esc_message *msg)
518 update_telemetrydata();
520 if (telestate->Settings.Sensor.ESC == HOTTBRIDGESETTINGS_SENSOR_DISABLED) {
521 return 0;
524 // clear message buffer
525 memset(msg, 0, sizeof(*msg));
527 // message header
528 msg->start = HOTT_START;
529 msg->stop = HOTT_STOP;
530 msg->sensor_id = HOTT_ESC_ID;
531 msg->warning = 0;
532 msg->sensor_text_id = HOTT_ESC_TEXT_ID;
534 // main batterie
535 float voltage = (telestate->Battery.Voltage > 0) ? telestate->Battery.Voltage : 0;
536 float current = (telestate->Battery.Current > 0) ? telestate->Battery.Current : 0;
537 float max_current = (telestate->Battery.PeakCurrent > 0) ? telestate->Battery.PeakCurrent : 0;
538 float energy = (telestate->Battery.ConsumedEnergy > 0) ? telestate->Battery.ConsumedEnergy : 0;
539 msg->batt_voltage = scale_float2uword(voltage, 10, 0);
540 msg->current = scale_float2uword(current, 10, 0);
541 msg->max_current = scale_float2uword(max_current, 10, 0);
542 msg->batt_capacity = scale_float2uword(energy, 0.1f, 0);
544 // temperatures
545 msg->temperatureESC = scale_float2uint8(telestate->Gyro.temperature, 1, OFFSET_TEMPERATURE);
546 msg->max_temperatureESC = scale_float2uint8(0, 1, OFFSET_TEMPERATURE);
547 msg->temperatureMOT = scale_float2uint8(telestate->Baro.Temperature, 1, OFFSET_TEMPERATURE);
548 msg->max_temperatureMOT = scale_float2uint8(0, 1, OFFSET_TEMPERATURE);
550 msg->checksum = calc_checksum((uint8_t *)msg, sizeof(*msg));
551 return sizeof(*msg);
554 uint16_t build_TEXT_message(struct hott_text_message *msg)
556 update_telemetrydata();
558 // clear message buffer
559 memset(msg, 0, sizeof(*msg));
561 // message header
562 msg->start = HOTT_START;
563 msg->stop = HOTT_STOP;
564 msg->sensor_id = HOTT_TEXT_ID;
566 msg->checksum = calc_checksum((uint8_t *)msg, sizeof(*msg));
567 return sizeof(*msg);
571 * update telemetry data
572 * this is called on every telemetry request
573 * calling interval is 200ms depending on TX
574 * 200ms telemetry request is used as time base for timed calculations (5Hz interval)
576 void update_telemetrydata()
578 // update all available data
579 if (HoTTBridgeSettingsHandle() != NULL) {
580 HoTTBridgeSettingsGet(&telestate->Settings);
582 if (AttitudeStateHandle() != NULL) {
583 AttitudeStateGet(&telestate->Attitude);
585 if (BaroSensorHandle() != NULL) {
586 BaroSensorGet(&telestate->Baro);
588 if (FlightBatteryStateHandle() != NULL) {
589 FlightBatteryStateGet(&telestate->Battery);
591 if (FlightStatusHandle() != NULL) {
592 FlightStatusGet(&telestate->FlightStatus);
594 if (GPSPositionSensorHandle() != NULL) {
595 GPSPositionSensorGet(&telestate->GPS);
597 if (GPSTimeHandle() != NULL) {
598 GPSTimeGet(&telestate->GPStime);
600 if (GyroSensorHandle() != NULL) {
601 GyroSensorGet(&telestate->Gyro);
603 if (HomeLocationHandle() != NULL) {
604 HomeLocationGet(&telestate->Home);
606 if (PositionStateHandle() != NULL) {
607 PositionStateGet(&telestate->Position);
609 if (SystemAlarmsHandle() != NULL) {
610 SystemAlarmsGet(&telestate->SysAlarms);
612 if (VelocityStateHandle() != NULL) {
613 VelocityStateGet(&telestate->Velocity);
616 // send actual climbrate value to ring buffer as mm per 0.2s values
617 uint8_t n = telestate->climbrate_pointer;
618 telestate->climbratebuffer[telestate->climbrate_pointer++] = -telestate->Velocity.Down * 200;
619 telestate->climbrate_pointer %= climbratesize;
621 // calculate avarage climbrates in meters per 1, 3 and 10 second(s) based on 200ms interval
622 telestate->climbrate1s = 0;
623 telestate->climbrate3s = 0;
624 telestate->climbrate10s = 0;
625 for (uint8_t i = 0; i < climbratesize; i++) {
626 telestate->climbrate1s += (i < 5) ? telestate->climbratebuffer[n] : 0;
627 telestate->climbrate3s += (i < 15) ? telestate->climbratebuffer[n] : 0;
628 telestate->climbrate10s += (i < 50) ? telestate->climbratebuffer[n] : 0;
629 n += climbratesize - 1;
630 n %= climbratesize;
632 telestate->climbrate1s = telestate->climbrate1s / 1000;
633 telestate->climbrate3s = telestate->climbrate3s / 1000;
634 telestate->climbrate10s = telestate->climbrate10s / 1000;
636 // set altitude offset and clear min/max values when arming
637 if ((telestate->FlightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING) || ((telestate->last_armed != FLIGHTSTATUS_ARMED_ARMED) && (telestate->FlightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED))) {
638 telestate->min_altitude = 0;
639 telestate->max_altitude = 0;
641 telestate->last_armed = telestate->FlightStatus.Armed;
643 // calculate altitude relative to start position
644 telestate->altitude = -telestate->Position.Down;
646 // check and set min/max values when armed.
647 if (telestate->FlightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) {
648 if (telestate->min_altitude > telestate->altitude) {
649 telestate->min_altitude = telestate->altitude;
651 if (telestate->max_altitude < telestate->altitude) {
652 telestate->max_altitude = telestate->altitude;
656 // gps home position and course
657 telestate->homedistance = sqrtf(telestate->Position.North * telestate->Position.North + telestate->Position.East * telestate->Position.East);
658 telestate->homecourse = acosf(-telestate->Position.North / telestate->homedistance) / 3.14159265f * 180;
659 if (telestate->Position.East > 0) {
660 telestate->homecourse = 360 - telestate->homecourse;
663 // statusline
664 const char *txt_unknown = "unknown";
665 const char *txt_manual = "Manual";
666 const char *txt_stabilized1 = "Stabilized1";
667 const char *txt_stabilized2 = "Stabilized2";
668 const char *txt_stabilized3 = "Stabilized3";
669 const char *txt_stabilized4 = "Stabilized4";
670 const char *txt_stabilized5 = "Stabilized5";
671 const char *txt_stabilized6 = "Stabilized6";
672 const char *txt_positionhold = "PositionHold";
673 const char *txt_courselock = "CourseLock";
674 const char *txt_velocityroam = "VelocityRoam";
675 const char *txt_homeleash = "HomeLeash";
676 const char *txt_absoluteposition = "AbsolutePosition";
677 const char *txt_returntobase = "ReturnToBase";
678 const char *txt_land = "Land";
679 const char *txt_pathplanner = "PathPlanner";
680 const char *txt_poi = "PointOfInterest";
681 const char *txt_autocruise = "AutoCruise";
682 const char *txt_autotakeoff = "AutoTakeOff";
683 const char *txt_autotune = "Autotune";
684 const char *txt_disarmed = "Disarmed";
685 const char *txt_arming = "Arming";
686 const char *txt_armed = "Armed";
688 const char *txt_flightmode;
689 switch (telestate->FlightStatus.FlightMode) {
690 case FLIGHTSTATUS_FLIGHTMODE_MANUAL:
691 txt_flightmode = txt_manual;
692 break;
693 case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
694 txt_flightmode = txt_stabilized1;
695 break;
696 case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
697 txt_flightmode = txt_stabilized2;
698 break;
699 case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
700 txt_flightmode = txt_stabilized3;
701 break;
702 case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
703 txt_flightmode = txt_stabilized4;
704 break;
705 case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
706 txt_flightmode = txt_stabilized5;
707 break;
708 case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
709 txt_flightmode = txt_stabilized6;
710 break;
711 case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
712 txt_flightmode = txt_positionhold;
713 break;
714 case FLIGHTSTATUS_FLIGHTMODE_COURSELOCK:
715 txt_flightmode = txt_courselock;
716 break;
717 case FLIGHTSTATUS_FLIGHTMODE_VELOCITYROAM:
718 txt_flightmode = txt_velocityroam;
719 break;
720 case FLIGHTSTATUS_FLIGHTMODE_HOMELEASH:
721 txt_flightmode = txt_homeleash;
722 break;
723 case FLIGHTSTATUS_FLIGHTMODE_ABSOLUTEPOSITION:
724 txt_flightmode = txt_absoluteposition;
725 break;
726 case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE:
727 txt_flightmode = txt_returntobase;
728 break;
729 case FLIGHTSTATUS_FLIGHTMODE_LAND:
730 txt_flightmode = txt_land;
731 break;
732 case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER:
733 txt_flightmode = txt_pathplanner;
734 break;
735 case FLIGHTSTATUS_FLIGHTMODE_POI:
736 txt_flightmode = txt_poi;
737 break;
738 case FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE:
739 txt_flightmode = txt_autocruise;
740 break;
741 case FLIGHTSTATUS_FLIGHTMODE_AUTOTAKEOFF:
742 txt_flightmode = txt_autotakeoff;
743 break;
744 case FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE:
745 txt_flightmode = txt_autotune;
746 break;
747 default:
748 txt_flightmode = txt_unknown;
751 const char *txt_armstate;
752 switch (telestate->FlightStatus.Armed) {
753 case FLIGHTSTATUS_ARMED_DISARMED:
754 txt_armstate = txt_disarmed;
755 break;
756 case FLIGHTSTATUS_ARMED_ARMING:
757 txt_armstate = txt_arming;
758 break;
759 case FLIGHTSTATUS_ARMED_ARMED:
760 txt_armstate = txt_armed;
761 break;
762 default:
763 txt_armstate = txt_unknown;
766 snprintf(telestate->statusline, sizeof(telestate->statusline), "%12s,%8s", txt_flightmode, txt_armstate);
770 * generate warning beeps or spoken announcements
772 uint8_t generate_warning()
774 // set warning tone with hardcoded priority
775 if ((telestate->Settings.Warning.MinSpeed == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
776 (telestate->Settings.Limit.MinSpeed > telestate->GPS.Groundspeed * MS_TO_KMH)) {
777 return HOTT_TONE_A; // maximum speed
779 if ((telestate->Settings.Warning.NegDifference2 == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
780 (telestate->Settings.Limit.NegDifference2 > telestate->climbrate3s)) {
781 return HOTT_TONE_B; // sink rate 3s
783 if ((telestate->Settings.Warning.NegDifference1 == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
784 (telestate->Settings.Limit.NegDifference1 > telestate->climbrate1s)) {
785 return HOTT_TONE_C; // sink rate 1s
787 if ((telestate->Settings.Warning.MaxDistance == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
788 (telestate->Settings.Limit.MaxDistance < telestate->homedistance)) {
789 return HOTT_TONE_D; // maximum distance
791 if ((telestate->Settings.Warning.MinSensor1Temp == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
792 (telestate->Settings.Limit.MinSensor1Temp > telestate->Gyro.temperature)) {
793 return HOTT_TONE_F; // minimum temperature sensor 1
795 if ((telestate->Settings.Warning.MinSensor2Temp == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
796 (telestate->Settings.Limit.MinSensor2Temp > telestate->Baro.Temperature)) {
797 return HOTT_TONE_G; // minimum temperature sensor 2
799 if ((telestate->Settings.Warning.MaxSensor1Temp == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
800 (telestate->Settings.Limit.MaxSensor1Temp < telestate->Gyro.temperature)) {
801 return HOTT_TONE_H; // maximum temperature sensor 1
803 if ((telestate->Settings.Warning.MaxSensor2Temp == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
804 (telestate->Settings.Limit.MaxSensor2Temp < telestate->Baro.Temperature)) {
805 return HOTT_TONE_I; // maximum temperature sensor 2
807 if ((telestate->Settings.Warning.MaxSpeed == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
808 (telestate->Settings.Limit.MaxSpeed < telestate->GPS.Groundspeed * MS_TO_KMH)) {
809 return HOTT_TONE_L; // maximum speed
811 if ((telestate->Settings.Warning.PosDifference2 == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
812 (telestate->Settings.Limit.PosDifference2 > telestate->climbrate3s)) {
813 return HOTT_TONE_M; // climb rate 3s
815 if ((telestate->Settings.Warning.PosDifference1 == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
816 (telestate->Settings.Limit.PosDifference1 > telestate->climbrate1s)) {
817 return HOTT_TONE_N; // climb rate 1s
819 if ((telestate->Settings.Warning.MinHeight == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
820 (telestate->Settings.Limit.MinHeight > telestate->altitude)) {
821 return HOTT_TONE_O; // minimum height
823 if ((telestate->Settings.Warning.MinPowerVoltage == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
824 (telestate->Settings.Limit.MinPowerVoltage > telestate->Battery.Voltage)) {
825 return HOTT_TONE_P; // minimum input voltage
827 if ((telestate->Settings.Warning.MaxUsedCapacity == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
828 (telestate->Settings.Limit.MaxUsedCapacity < telestate->Battery.ConsumedEnergy)) {
829 return HOTT_TONE_V; // capacity
831 if ((telestate->Settings.Warning.MaxCurrent == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
832 (telestate->Settings.Limit.MaxCurrent < telestate->Battery.Current)) {
833 return HOTT_TONE_W; // maximum current
835 if ((telestate->Settings.Warning.MaxPowerVoltage == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
836 (telestate->Settings.Limit.MaxPowerVoltage < telestate->Battery.Voltage)) {
837 return HOTT_TONE_X; // maximum input voltage
839 if ((telestate->Settings.Warning.MaxHeight == HOTTBRIDGESETTINGS_WARNING_ENABLED) &&
840 (telestate->Settings.Limit.MaxHeight < telestate->altitude)) {
841 return HOTT_TONE_Z; // maximum height
843 // altitude beeps when crossing altitude limits at 20,40,60,80,100,200,400,600,800 and 1000 meters
844 if (telestate->Settings.Warning.AltitudeBeep == HOTTBRIDGESETTINGS_WARNING_ENABLED) {
845 // update altitude when checked for beeps
846 float last = telestate->altitude_last;
847 float actual = telestate->altitude;
848 telestate->altitude_last = telestate->altitude;
849 if (((last < 20) && (actual >= 20)) || ((last > 20) && (actual <= 20))) {
850 return HOTT_TONE_20M;
852 if (((last < 40) && (actual >= 40)) || ((last > 40) && (actual <= 40))) {
853 return HOTT_TONE_40M;
855 if (((last < 60) && (actual >= 60)) || ((last > 60) && (actual <= 60))) {
856 return HOTT_TONE_60M;
858 if (((last < 80) && (actual >= 80)) || ((last > 80) && (actual <= 80))) {
859 return HOTT_TONE_80M;
861 if (((last < 100) && (actual >= 100)) || ((last > 100) && (actual <= 100))) {
862 return HOTT_TONE_100M;
864 if (((last < 200) && (actual >= 200)) || ((last > 200) && (actual <= 200))) {
865 return HOTT_TONE_200M;
867 if (((last < 400) && (actual >= 400)) || ((last > 400) && (actual <= 400))) {
868 return HOTT_TONE_400M;
870 if (((last < 600) && (actual >= 600)) || ((last > 600) && (actual <= 600))) {
871 return HOTT_TONE_600M;
873 if (((last < 800) && (actual >= 800)) || ((last > 800) && (actual <= 800))) {
874 return HOTT_TONE_800M;
876 if (((last < 1000) && (actual >= 1000)) || ((last > 1000) && (actual <= 1000))) {
877 return HOTT_TONE_1000M;
881 // there is no warning
882 return 0;
886 * calculate checksum of data buffer
888 uint8_t calc_checksum(uint8_t *data, uint16_t size)
890 uint16_t sum = 0;
892 for (int i = 0; i < size; i++) {
893 sum += data[i];
895 return sum;
899 * scale float value with scale and offset to unsigned byte
901 uint8_t scale_float2uint8(float value, float scale, float offset)
903 uint16_t temp = (uint16_t)roundf(value * scale + offset);
904 uint8_t result;
906 result = (uint8_t)temp & 0xff;
907 return result;
911 * scale float value with scale and offset to signed byte (int8_t)
913 int8_t scale_float2int8(float value, float scale, float offset)
915 int8_t result = (int8_t)roundf(value * scale + offset);
917 return result;
921 * scale float value with scale and offset to word
923 uword_t scale_float2uword(float value, float scale, float offset)
925 uint16_t temp = (uint16_t)roundf(value * scale + offset);
926 uword_t result;
928 result.l = (uint8_t)temp & 0xff;
929 result.h = (uint8_t)(temp >> 8) & 0xff;
930 return result;
934 * convert dword gps value into HoTT gps format and write result to given pointers
936 void convert_long2gps(int32_t value, uint8_t *dir, uword_t *min, uword_t *sec)
938 // convert gps decigrad value into degrees, minutes and seconds
939 uword_t temp;
940 uint32_t absvalue = abs(value);
941 uint16_t degrees = (absvalue / 10000000);
942 uint32_t seconds = (absvalue - degrees * 10000000) * 6;
943 uint16_t minutes = seconds / 1000000;
945 seconds %= 1000000;
946 seconds = seconds / 100;
947 uint16_t degmin = degrees * 100 + minutes;
948 // write results
949 *dir = (value < 0) ? 1 : 0;
950 temp.l = (uint8_t)degmin & 0xff;
951 temp.h = (uint8_t)(degmin >> 8) & 0xff;
952 *min = temp;
953 temp.l = (uint8_t)seconds & 0xff;
954 temp.h = (uint8_t)(seconds >> 8) & 0xff;
955 *sec = temp;
958 #endif // PIOS_INCLUDE_HOTT_BRIDGE
960 * @}
961 * @}