123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975 |
- #include "AP_Frsky_Telem.h"
- #include <AP_AHRS/AP_AHRS.h>
- #include <AP_BattMonitor/AP_BattMonitor.h>
- #include <AP_RangeFinder/AP_RangeFinder.h>
- #include <AP_Common/AP_FWVersion.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AP_Common/Location.h>
- #include <AP_GPS/AP_GPS.h>
- #include <stdio.h>
- extern const AP_HAL::HAL& hal;
- AP_Frsky_Telem::AP_Frsky_Telem(void) :
- _statustext_queue(FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY)
- {
- }
- bool AP_Frsky_Telem::init()
- {
- const AP_SerialManager &serial_manager = AP::serialmanager();
-
- if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) {
- _protocol = AP_SerialManager::SerialProtocol_FrSky_D;
- } else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort, 0))) {
- _protocol = AP_SerialManager::SerialProtocol_FrSky_SPort;
- } else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough, 0))) {
- _protocol = AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough;
-
-
- const char* _frame_string = gcs().frame_string();
- if (_frame_string == nullptr) {
- queue_message(MAV_SEVERITY_INFO, AP::fwversion().fw_string);
- } else {
- char firmware_buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
- snprintf(firmware_buf, sizeof(firmware_buf), "%s %s", AP::fwversion().fw_string, _frame_string);
- queue_message(MAV_SEVERITY_INFO, firmware_buf);
- }
- }
-
- if (_port != nullptr) {
- if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Frsky_Telem::loop, void),
- "FrSky",
- 1024, AP_HAL::Scheduler::PRIORITY_RCIN, 1)) {
- return false;
- }
-
- _port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
- return true;
- }
- return false;
- }
- void AP_Frsky_Telem::send_SPort_Passthrough(void)
- {
- int16_t numc;
- numc = _port->available();
-
- if (numc < 0) {
- return;
- }
-
- if (_port->txspace() < 19) {
- return;
- }
-
- uint8_t prev_byte = 0;
- for (int16_t i = 0; i < numc; i++) {
- prev_byte = _passthrough.new_byte;
- _passthrough.new_byte = _port->read();
- }
- if ((prev_byte == START_STOP_SPORT) && (_passthrough.new_byte == SENSOR_ID_28)) {
- if (_passthrough.send_chunk) {
- _passthrough.send_chunk = false;
- if (get_next_msg_chunk()) {
- send_uint32(DIY_FIRST_ID, _msg_chunk.chunk);
- }
- } else {
-
- check_sensor_status_flags();
-
- check_ekf_status();
-
- if (!_statustext_queue.empty()) {
- _passthrough.send_chunk = true;
- }
- if (_passthrough.send_attiandrng) {
- _passthrough.send_attiandrng = false;
- } else {
- _passthrough.send_attiandrng = true;
- uint32_t now = AP_HAL::millis();
- if ((now - _passthrough.params_timer) >= 1000) {
- send_uint32(DIY_FIRST_ID+7, calc_param());
- _passthrough.params_timer = AP_HAL::millis();
- return;
- }
- if ((now - _passthrough.ap_status_timer) >= 500) {
- if (gcs().vehicle_initialised()) {
- send_uint32(DIY_FIRST_ID+1, calc_ap_status());
- _passthrough.ap_status_timer = AP_HAL::millis();
- return;
- }
- }
- if ((now - _passthrough.batt_timer) >= 1000) {
- send_uint32(DIY_FIRST_ID+3, calc_batt(0));
- _passthrough.batt_timer = AP_HAL::millis();
- return;
- }
- if (AP::battery().num_instances() > 1) {
- if ((now - _passthrough.batt_timer2) >= 1000) {
- send_uint32(DIY_FIRST_ID+8, calc_batt(1));
- _passthrough.batt_timer2 = AP_HAL::millis();
- return;
- }
- }
- if ((now - _passthrough.gps_status_timer) >= 1000) {
- send_uint32(DIY_FIRST_ID+2, calc_gps_status());
- _passthrough.gps_status_timer = AP_HAL::millis();
- return;
- }
- if ((now - _passthrough.home_timer) >= 500) {
- send_uint32(DIY_FIRST_ID+4, calc_home());
- _passthrough.home_timer = AP_HAL::millis();
- return;
- }
- if ((now - _passthrough.velandyaw_timer) >= 500) {
- send_uint32(DIY_FIRST_ID+5, calc_velandyaw());
- _passthrough.velandyaw_timer = AP_HAL::millis();
- return;
- }
- if ((now - _passthrough.gps_latlng_timer) >= 1000) {
- send_uint32(GPS_LONG_LATI_FIRST_ID, calc_gps_latlng(&_passthrough.send_latitude));
- if (!_passthrough.send_latitude) {
- _passthrough.gps_latlng_timer = AP_HAL::millis();
- }
- return;
- }
- }
-
- send_uint32(DIY_FIRST_ID+6, calc_attiandrng());
- }
- }
- }
- void AP_Frsky_Telem::send_SPort(void)
- {
- const AP_AHRS &_ahrs = AP::ahrs();
- int16_t numc;
- numc = _port->available();
-
- if (numc < 0) {
- return;
- }
-
- if (_port->txspace() < 19) {
- return;
- }
- for (int16_t i = 0; i < numc; i++) {
- int16_t readbyte = _port->read();
- if (_SPort.sport_status == false) {
- if (readbyte == START_STOP_SPORT) {
- _SPort.sport_status = true;
- }
- } else {
- const AP_BattMonitor &_battery = AP::battery();
- switch(readbyte) {
- case SENSOR_ID_FAS:
- switch (_SPort.fas_call) {
- case 0:
- send_uint32(DATA_ID_FUEL, (uint16_t)roundf(_battery.capacity_remaining_pct()));
- break;
- case 1:
- send_uint32(DATA_ID_VFAS, (uint16_t)roundf(_battery.voltage() * 10.0f));
- break;
- case 2:
- {
- float current;
- if (!_battery.current_amps(current)) {
- current = 0;
- }
- send_uint32(DATA_ID_CURRENT, (uint16_t)roundf(current * 10.0f));
- break;
- }
- }
- if (_SPort.fas_call++ > 2) _SPort.fas_call = 0;
- break;
- case SENSOR_ID_GPS:
- switch (_SPort.gps_call) {
- case 0:
- calc_gps_position();
- send_uint32(DATA_ID_GPS_LAT_BP, _gps.latdddmm);
- break;
- case 1:
- send_uint32(DATA_ID_GPS_LAT_AP, _gps.latmmmm);
- break;
- case 2:
- send_uint32(DATA_ID_GPS_LAT_NS, _gps.lat_ns);
- break;
- case 3:
- send_uint32(DATA_ID_GPS_LONG_BP, _gps.londddmm);
- break;
- case 4:
- send_uint32(DATA_ID_GPS_LONG_AP, _gps.lonmmmm);
- break;
- case 5:
- send_uint32(DATA_ID_GPS_LONG_EW, _gps.lon_ew);
- break;
- case 6:
- send_uint32(DATA_ID_GPS_SPEED_BP, _gps.speed_in_meter);
- break;
- case 7:
- send_uint32(DATA_ID_GPS_SPEED_AP, _gps.speed_in_centimeter);
- break;
- case 8:
- send_uint32(DATA_ID_GPS_ALT_BP, _gps.alt_gps_meters);
- break;
- case 9:
- send_uint32(DATA_ID_GPS_ALT_AP, _gps.alt_gps_cm);
- break;
- case 10:
- send_uint32(DATA_ID_GPS_COURS_BP, (uint16_t)((_ahrs.yaw_sensor / 100) % 360));
- break;
- }
- if (_SPort.gps_call++ > 10) _SPort.gps_call = 0;
- break;
- case SENSOR_ID_VARIO:
- switch (_SPort.vario_call) {
- case 0 :
- calc_nav_alt();
- send_uint32(DATA_ID_BARO_ALT_BP, _gps.alt_nav_meters);
- break;
- case 1:
- send_uint32(DATA_ID_BARO_ALT_AP, _gps.alt_nav_cm);
- break;
- }
- if (_SPort.vario_call++ > 1) _SPort.vario_call = 0;
- break;
- case SENSOR_ID_SP2UR:
- switch (_SPort.various_call) {
- case 0 :
- send_uint32(DATA_ID_TEMP2, (uint16_t)(AP::gps().num_sats() * 10 + AP::gps().status()));
- break;
- case 1:
- send_uint32(DATA_ID_TEMP1, gcs().custom_mode());
- break;
- }
- if (_SPort.various_call++ > 1) _SPort.various_call = 0;
- break;
- }
- _SPort.sport_status = false;
- }
- }
- }
- void AP_Frsky_Telem::send_D(void)
- {
- const AP_AHRS &_ahrs = AP::ahrs();
- const AP_BattMonitor &_battery = AP::battery();
- uint32_t now = AP_HAL::millis();
-
- if (now - _D.last_200ms_frame >= 200) {
- _D.last_200ms_frame = now;
- send_uint16(DATA_ID_TEMP2, (uint16_t)(AP::gps().num_sats() * 10 + AP::gps().status()));
- send_uint16(DATA_ID_TEMP1, gcs().custom_mode());
- send_uint16(DATA_ID_FUEL, (uint16_t)roundf(_battery.capacity_remaining_pct()));
- send_uint16(DATA_ID_VFAS, (uint16_t)roundf(_battery.voltage() * 10.0f));
- float current;
- if (!_battery.current_amps(current)) {
- current = 0;
- }
- send_uint16(DATA_ID_CURRENT, (uint16_t)roundf(current * 10.0f));
- calc_nav_alt();
- send_uint16(DATA_ID_BARO_ALT_BP, _gps.alt_nav_meters);
- send_uint16(DATA_ID_BARO_ALT_AP, _gps.alt_nav_cm);
- }
-
- if (now - _D.last_1000ms_frame >= 1000) {
- _D.last_1000ms_frame = now;
- send_uint16(DATA_ID_GPS_COURS_BP, (uint16_t)((_ahrs.yaw_sensor / 100) % 360));
- calc_gps_position();
- if (AP::gps().status() >= 3) {
- send_uint16(DATA_ID_GPS_LAT_BP, _gps.latdddmm);
- send_uint16(DATA_ID_GPS_LAT_AP, _gps.latmmmm);
- send_uint16(DATA_ID_GPS_LAT_NS, _gps.lat_ns);
- send_uint16(DATA_ID_GPS_LONG_BP, _gps.londddmm);
- send_uint16(DATA_ID_GPS_LONG_AP, _gps.lonmmmm);
- send_uint16(DATA_ID_GPS_LONG_EW, _gps.lon_ew);
- send_uint16(DATA_ID_GPS_SPEED_BP, _gps.speed_in_meter);
- send_uint16(DATA_ID_GPS_SPEED_AP, _gps.speed_in_centimeter);
- send_uint16(DATA_ID_GPS_ALT_BP, _gps.alt_gps_meters);
- send_uint16(DATA_ID_GPS_ALT_AP, _gps.alt_gps_cm);
- }
- }
- }
- void AP_Frsky_Telem::loop(void)
- {
-
- if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) {
- _port->begin(AP_SERIALMANAGER_FRSKY_D_BAUD, AP_SERIALMANAGER_FRSKY_BUFSIZE_RX, AP_SERIALMANAGER_FRSKY_BUFSIZE_TX);
- } else {
- _port->begin(AP_SERIALMANAGER_FRSKY_SPORT_BAUD, AP_SERIALMANAGER_FRSKY_BUFSIZE_RX, AP_SERIALMANAGER_FRSKY_BUFSIZE_TX);
- }
- _port->set_unbuffered_writes(true);
- while (true) {
- hal.scheduler->delay(1);
- if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) {
- send_D();
- } else if (_protocol == AP_SerialManager::SerialProtocol_FrSky_SPort) {
- send_SPort();
- } else if (_protocol == AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough) {
- send_SPort_Passthrough();
- }
- }
- }
- void AP_Frsky_Telem::calc_crc(uint8_t byte)
- {
- _crc += byte;
- _crc += _crc >> 8;
- _crc &= 0xFF;
- }
- void AP_Frsky_Telem::send_crc(void)
- {
- send_byte(0xFF - _crc);
- _crc = 0;
- }
- void AP_Frsky_Telem::send_byte(uint8_t byte)
- {
- if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) {
- if (byte == START_STOP_D) {
- _port->write(0x5D);
- _port->write(0x3E);
- } else if (byte == BYTESTUFF_D) {
- _port->write(0x5D);
- _port->write(0x3D);
- } else {
- _port->write(byte);
- }
- } else {
- if (byte == START_STOP_SPORT) {
- _port->write(0x7D);
- _port->write(0x5E);
- } else if (byte == BYTESTUFF_SPORT) {
- _port->write(0x7D);
- _port->write(0x5D);
- } else {
- _port->write(byte);
- }
- calc_crc(byte);
- }
- }
- void AP_Frsky_Telem::send_uint32(uint16_t id, uint32_t data)
- {
- send_byte(0x10);
- uint8_t *bytes = (uint8_t*)&id;
- send_byte(bytes[0]);
- send_byte(bytes[1]);
- bytes = (uint8_t*)&data;
- send_byte(bytes[0]);
- send_byte(bytes[1]);
- send_byte(bytes[2]);
- send_byte(bytes[3]);
- send_crc();
- }
- void AP_Frsky_Telem::send_uint16(uint16_t id, uint16_t data)
- {
- _port->write(START_STOP_D);
- uint8_t *bytes = (uint8_t*)&id;
- send_byte(bytes[0]);
- bytes = (uint8_t*)&data;
- send_byte(bytes[0]);
- send_byte(bytes[1]);
- }
- bool AP_Frsky_Telem::get_next_msg_chunk(void)
- {
- if (_statustext_queue.empty()) {
- return false;
- }
- if (_msg_chunk.repeats == 0) {
- uint8_t character = 0;
- _msg_chunk.chunk = 0;
- for (int i = 3; i > -1 && _msg_chunk.char_index < sizeof(_statustext_queue[0]->text); i--) {
- character = _statustext_queue[0]->text[_msg_chunk.char_index++];
- if (!character) {
- break;
- }
- _msg_chunk.chunk |= character << i * 8;
- }
- if (!character || (_msg_chunk.char_index == sizeof(_statustext_queue[0]->text))) {
- _msg_chunk.char_index = 0;
-
- _msg_chunk.chunk |= (_statustext_queue[0]->severity & 0x4)<<21;
- _msg_chunk.chunk |= (_statustext_queue[0]->severity & 0x2)<<14;
- _msg_chunk.chunk |= (_statustext_queue[0]->severity & 0x1)<<7;
- }
- }
- if (_msg_chunk.repeats++ > 2) {
- _msg_chunk.repeats = 0;
- if (_msg_chunk.char_index == 0) {
- _statustext_queue.remove(0);
- }
- }
- return true;
- }
- void AP_Frsky_Telem::queue_message(MAV_SEVERITY severity, const char *text)
- {
- mavlink_statustext_t statustext{};
- statustext.severity = severity;
- strncpy(statustext.text, text, sizeof(statustext.text));
-
-
-
- _statustext_queue.push_force(statustext);
- }
- void AP_Frsky_Telem::check_sensor_status_flags(void)
- {
- uint32_t now = AP_HAL::millis();
- const uint32_t _sensor_status_flags = sensor_status_flags();
- if ((now - check_sensor_status_timer) >= 5000) {
-
- if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_GPS) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad GPS Health");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_GYRO) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad Gyro Health");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_ACCEL) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad Accel Health");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_3D_MAG) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad Compass Health");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad Baro Health");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_LASER_POSITION) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad LiDAR Health");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad OptFlow Health");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_TERRAIN) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad or No Terrain Data");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_GEOFENCE) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Geofence Breach");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_AHRS) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad AHRS");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_RC_RECEIVER) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "No RC Receiver");
- check_sensor_status_timer = now;
- } else if ((_sensor_status_flags & MAV_SYS_STATUS_LOGGING) > 0) {
- queue_message(MAV_SEVERITY_CRITICAL, "Bad Logging");
- check_sensor_status_timer = now;
- }
- }
- }
- void AP_Frsky_Telem::check_ekf_status(void)
- {
- const AP_AHRS &_ahrs = AP::ahrs();
-
- float velVar, posVar, hgtVar, tasVar;
- Vector3f magVar;
- Vector2f offset;
- if (_ahrs.get_variances(velVar, posVar, hgtVar, magVar, tasVar, offset)) {
- uint32_t now = AP_HAL::millis();
- if ((now - check_ekf_status_timer) >= 10000) {
-
- if (velVar >= 1) {
- queue_message(MAV_SEVERITY_CRITICAL, "Error velocity variance");
- check_ekf_status_timer = now;
- }
- if (posVar >= 1) {
- queue_message(MAV_SEVERITY_CRITICAL, "Error pos horiz variance");
- check_ekf_status_timer = now;
- }
- if (hgtVar >= 1) {
- queue_message(MAV_SEVERITY_CRITICAL, "Error pos vert variance");
- check_ekf_status_timer = now;
- }
- if (magVar.length() >= 1) {
- queue_message(MAV_SEVERITY_CRITICAL, "Error compass variance");
- check_ekf_status_timer = now;
- }
- if (tasVar >= 1) {
- queue_message(MAV_SEVERITY_CRITICAL, "Error terrain alt variance");
- check_ekf_status_timer = now;
- }
- }
- }
- }
-
- uint32_t AP_Frsky_Telem::calc_param(void)
- {
- const AP_BattMonitor &_battery = AP::battery();
- uint32_t param = 0;
-
- if (_paramID >= 5) {
- _paramID = 0;
- }
- _paramID++;
- switch(_paramID) {
- case 1:
- param = gcs().frame_type();
- break;
- case 2:
- case 3:
- break;
- case 4:
- param = (uint32_t)roundf(_battery.pack_capacity_mah(0));
- break;
- case 5:
- param = (uint32_t)roundf(_battery.pack_capacity_mah(1));
- break;
- }
-
- param = (_paramID << PARAM_ID_OFFSET) | (param & PARAM_VALUE_LIMIT);
-
- return param;
- }
- uint32_t AP_Frsky_Telem::calc_gps_latlng(bool *send_latitude)
- {
- uint32_t latlng;
- const Location &loc = AP::gps().location(0);
-
- if ((*send_latitude) == true) {
- if (loc.lat < 0) {
- latlng = ((labs(loc.lat)/100)*6) | 0x40000000;
- } else {
- latlng = ((labs(loc.lat)/100)*6);
- }
- (*send_latitude) = false;
- } else {
- if (loc.lng < 0) {
- latlng = ((labs(loc.lng)/100)*6) | 0xC0000000;
- } else {
- latlng = ((labs(loc.lng)/100)*6) | 0x80000000;
- }
- (*send_latitude) = true;
- }
- return latlng;
- }
- uint32_t AP_Frsky_Telem::calc_gps_status(void)
- {
- const AP_GPS &gps = AP::gps();
- uint32_t gps_status;
-
- gps_status = (gps.num_sats() < GPS_SATS_LIMIT) ? gps.num_sats() : GPS_SATS_LIMIT;
-
- gps_status |= ((gps.status() < GPS_STATUS_LIMIT) ? gps.status() : GPS_STATUS_LIMIT)<<GPS_STATUS_OFFSET;
-
- gps_status |= prep_number(roundf(gps.get_hdop() * 0.1f),2,1)<<GPS_HDOP_OFFSET;
-
- gps_status |= ((gps.status() > GPS_STATUS_LIMIT) ? gps.status()-GPS_STATUS_LIMIT : 0)<<GPS_ADVSTATUS_OFFSET;
-
- const Location &loc = gps.location();
- gps_status |= prep_number(roundf(loc.alt * 0.1f),2,2)<<GPS_ALTMSL_OFFSET;
- return gps_status;
- }
- uint32_t AP_Frsky_Telem::calc_batt(uint8_t instance)
- {
- const AP_BattMonitor &_battery = AP::battery();
- uint32_t batt;
- float current, consumed_mah;
- if (!_battery.current_amps(current, instance)) {
- current = 0;
- }
- if (!_battery.consumed_mah(consumed_mah, instance)) {
- consumed_mah = 0;
- }
-
-
- batt = (((uint16_t)roundf(_battery.voltage(instance) * 10.0f)) & BATT_VOLTAGE_LIMIT);
-
- batt |= prep_number(roundf(current * 10.0f), 2, 1)<<BATT_CURRENT_OFFSET;
-
- batt |= ((consumed_mah < BATT_TOTALMAH_LIMIT) ? ((uint16_t)roundf(consumed_mah) & BATT_TOTALMAH_LIMIT) : BATT_TOTALMAH_LIMIT)<<BATT_TOTALMAH_OFFSET;
- return batt;
- }
- uint32_t AP_Frsky_Telem::calc_ap_status(void)
- {
- uint32_t ap_status;
-
- uint8_t imu_temp = (uint8_t) roundf(constrain_float(AP::ins().get_temperature(0), AP_IMU_TEMP_MIN, AP_IMU_TEMP_MAX) - AP_IMU_TEMP_MIN);
-
- ap_status = (uint8_t)((gcs().custom_mode()+1) & AP_CONTROL_MODE_LIMIT);
-
- ap_status |= (uint8_t)(gcs().simple_input_active())<<AP_SIMPLE_OFFSET;
- ap_status |= (uint8_t)(gcs().supersimple_input_active())<<AP_SSIMPLE_OFFSET;
-
- ap_status |= (uint8_t)(AP_Notify::flags.flying) << AP_FLYING_OFFSET;
-
- ap_status |= (uint8_t)(AP_Notify::flags.armed)<<AP_ARMED_OFFSET;
-
- ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery)<<AP_BATT_FS_OFFSET;
-
- ap_status |= (uint8_t)(AP_Notify::flags.ekf_bad)<<AP_EKF_FS_OFFSET;
-
- ap_status |= imu_temp << AP_IMU_TEMP_OFFSET;
- return ap_status;
- }
- uint32_t AP_Frsky_Telem::calc_home(void)
- {
- const AP_AHRS &_ahrs = AP::ahrs();
- uint32_t home = 0;
- Location loc;
- float _relative_home_altitude = 0;
- if (_ahrs.get_position(loc)) {
-
- const Location &home_loc = _ahrs.get_home();
- if (home_loc.lat != 0 || home_loc.lng != 0) {
-
- home = prep_number(roundf(home_loc.get_distance(loc)), 3, 2);
-
- home |= (((uint8_t)roundf(loc.get_bearing_to(home_loc) * 0.00333f)) & HOME_BEARING_LIMIT)<<HOME_BEARING_OFFSET;
- }
-
- _relative_home_altitude = loc.alt;
- if (!loc.relative_alt) {
-
- _relative_home_altitude -= _ahrs.get_home().alt;
- }
- }
-
- home |= prep_number(roundf(_relative_home_altitude * 0.1f), 3, 2)<<HOME_ALT_OFFSET;
- return home;
- }
- uint32_t AP_Frsky_Telem::calc_velandyaw(void)
- {
- AP_AHRS &_ahrs = AP::ahrs();
- uint32_t velandyaw;
- Vector3f velNED {};
-
- if (!_ahrs.get_velocity_NED(velNED)) {
- velNED.zero();
- }
-
- velandyaw = prep_number(roundf(-velNED.z * 10), 2, 1);
-
- const AP_Airspeed *aspeed = _ahrs.get_airspeed();
- if (aspeed && aspeed->enabled()) {
- velandyaw |= prep_number(roundf(aspeed->get_airspeed() * 10), 2, 1)<<VELANDYAW_XYVEL_OFFSET;
- } else {
- velandyaw |= prep_number(roundf(_ahrs.groundspeed() * 10), 2, 1)<<VELANDYAW_XYVEL_OFFSET;
- }
-
- velandyaw |= ((uint16_t)roundf(_ahrs.yaw_sensor * 0.05f) & VELANDYAW_YAW_LIMIT)<<VELANDYAW_YAW_OFFSET;
- return velandyaw;
- }
- uint32_t AP_Frsky_Telem::calc_attiandrng(void)
- {
- const AP_AHRS &_ahrs = AP::ahrs();
- const RangeFinder *_rng = RangeFinder::get_singleton();
- uint32_t attiandrng;
-
- attiandrng = ((uint16_t)roundf((_ahrs.roll_sensor + 18000) * 0.05f) & ATTIANDRNG_ROLL_LIMIT);
-
- attiandrng |= ((uint16_t)roundf((_ahrs.pitch_sensor + 9000) * 0.05f) & ATTIANDRNG_PITCH_LIMIT)<<ATTIANDRNG_PITCH_OFFSET;
-
- attiandrng |= prep_number(_rng ? _rng->distance_cm_orient(ROTATION_PITCH_270) : 0, 3, 1)<<ATTIANDRNG_RNGFND_OFFSET;
- return attiandrng;
- }
- uint16_t AP_Frsky_Telem::prep_number(int32_t number, uint8_t digits, uint8_t power)
- {
- uint16_t res = 0;
- uint32_t abs_number = abs(number);
- if ((digits == 2) && (power == 1)) {
- if (abs_number < 100) {
- res = abs_number<<1;
- } else if (abs_number < 1270) {
- res = ((uint8_t)roundf(abs_number * 0.1f)<<1)|0x1;
- } else {
- res = 0xFF;
- }
- if (number < 0) {
- res |= 0x1<<8;
- }
- } else if ((digits == 2) && (power == 2)) {
- if (abs_number < 100) {
- res = abs_number<<2;
- } else if (abs_number < 1000) {
- res = ((uint8_t)roundf(abs_number * 0.1f)<<2)|0x1;
- } else if (abs_number < 10000) {
- res = ((uint8_t)roundf(abs_number * 0.01f)<<2)|0x2;
- } else if (abs_number < 127000) {
- res = ((uint8_t)roundf(abs_number * 0.001f)<<2)|0x3;
- } else {
- res = 0x1FF;
- }
- if (number < 0) {
- res |= 0x1<<9;
- }
- } else if ((digits == 3) && (power == 1)) {
- if (abs_number < 1000) {
- res = abs_number<<1;
- } else if (abs_number < 10240) {
- res = ((uint16_t)roundf(abs_number * 0.1f)<<1)|0x1;
- } else {
- res = 0x7FF;
- }
- if (number < 0) {
- res |= 0x1<<11;
- }
- } else if ((digits == 3) && (power == 2)) {
- if (abs_number < 1000) {
- res = abs_number<<2;
- } else if (abs_number < 10000) {
- res = ((uint16_t)roundf(abs_number * 0.1f)<<2)|0x1;
- } else if (abs_number < 100000) {
- res = ((uint16_t)roundf(abs_number * 0.01f)<<2)|0x2;
- } else if (abs_number < 1024000) {
- res = ((uint16_t)roundf(abs_number * 0.001f)<<2)|0x3;
- } else {
- res = 0xFFF;
- }
- if (number < 0) {
- res |= 0x1<<12;
- }
- }
- return res;
- }
- void AP_Frsky_Telem::calc_nav_alt(void)
- {
- const AP_AHRS &_ahrs = AP::ahrs();
- Location loc;
- float current_height = 0;
- if (_ahrs.get_position(loc)) {
- current_height = loc.alt*0.01f;
- if (!loc.relative_alt) {
-
- current_height -= _ahrs.get_home().alt*0.01f;
- }
- }
-
- _gps.alt_nav_meters = (int16_t)current_height;
- _gps.alt_nav_cm = (current_height - _gps.alt_nav_meters) * 100;
- }
- float AP_Frsky_Telem::format_gps(float dec)
- {
- uint8_t dm_deg = (uint8_t) dec;
- return (dm_deg * 100.0f) + (dec - dm_deg) * 60;
- }
- void AP_Frsky_Telem::calc_gps_position(void)
- {
- float lat;
- float lon;
- float alt;
- float speed;
- if (AP::gps().status() >= 3) {
- const Location &loc = AP::gps().location();
- lat = format_gps(fabsf(loc.lat/10000000.0f));
- _gps.latdddmm = lat;
- _gps.latmmmm = (lat - _gps.latdddmm) * 10000;
- _gps.lat_ns = (loc.lat < 0) ? 'S' : 'N';
- lon = format_gps(fabsf(loc.lng/10000000.0f));
- _gps.londddmm = lon;
- _gps.lonmmmm = (lon - _gps.londddmm) * 10000;
- _gps.lon_ew = (loc.lng < 0) ? 'W' : 'E';
- alt = loc.alt * 0.01f;
- _gps.alt_gps_meters = (int16_t)alt;
- _gps.alt_gps_cm = (alt - _gps.alt_gps_meters) * 100;
- speed = AP::gps().ground_speed();
- _gps.speed_in_meter = speed;
- _gps.speed_in_centimeter = (speed - _gps.speed_in_meter) * 100;
- } else {
- _gps.latdddmm = 0;
- _gps.latmmmm = 0;
- _gps.lat_ns = 0;
- _gps.londddmm = 0;
- _gps.lonmmmm = 0;
- _gps.alt_gps_meters = 0;
- _gps.alt_gps_cm = 0;
- _gps.speed_in_meter = 0;
- _gps.speed_in_centimeter = 0;
- }
- }
- uint32_t AP_Frsky_Telem::sensor_status_flags() const
- {
- uint32_t present;
- uint32_t enabled;
- uint32_t health;
- gcs().get_sensor_status_flags(present, enabled, health);
- return ~health & enabled & present;
- }
|