Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp
Views: 1798
#include "AP_Frsky_SPort_Passthrough.h"12#if AP_FRSKY_SPORT_PASSTHROUGH_ENABLED34#include <AP_AHRS/AP_AHRS.h>5#include <AP_BattMonitor/AP_BattMonitor.h>6#include <AP_GPS/AP_GPS.h>7#include <AP_HAL/utility/RingBuffer.h>8#include <AP_InertialSensor/AP_InertialSensor.h>9#include <AP_Notify/AP_Notify.h>10#include <AP_RangeFinder/AP_RangeFinder.h>11#include <AP_RPM/AP_RPM.h>12#include <AP_Terrain/AP_Terrain.h>13#include <AC_Fence/AC_Fence.h>14#include <AP_Vehicle/AP_Vehicle.h>15#include <GCS_MAVLink/GCS.h>16#if APM_BUILD_TYPE(APM_BUILD_Rover)17#include <AP_WindVane/AP_WindVane.h>18#endif1920#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL21#include "AP_Frsky_MAVlite.h"22#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL23#include "AP_Frsky_Parameters.h"2425/*26for FrSky SPort Passthrough27*/28// data bits preparation29// for parameter data30#define PARAM_ID_OFFSET 2431#define PARAM_VALUE_LIMIT 0xFFFFFF32// for gps status data33#define GPS_SATS_LIMIT 0xF34#define GPS_STATUS_LIMIT 0x335#define GPS_STATUS_OFFSET 436#define GPS_HDOP_OFFSET 637#define GPS_ADVSTATUS_OFFSET 1438#define GPS_ALTMSL_OFFSET 2239// for battery data40#define BATT_VOLTAGE_LIMIT 0x1FF41#define BATT_CURRENT_OFFSET 942#define BATT_TOTALMAH_LIMIT 0x7FFF43#define BATT_TOTALMAH_OFFSET 1744// for autopilot status data45#define AP_CONTROL_MODE_LIMIT 0x1F46#define AP_SIMPLE_OFFSET 547#define AP_SSIMPLE_OFFSET 648#define AP_FLYING_OFFSET 749#define AP_ARMED_OFFSET 850#define AP_BATT_FS_OFFSET 951#define AP_EKF_FS_OFFSET 1052#define AP_FS_OFFSET 1253#define AP_FENCE_PRESENT_OFFSET 1354#define AP_FENCE_BREACH_OFFSET 1455#define AP_THROTTLE_OFFSET 1956#define AP_IMU_TEMP_MIN 19.0f57#define AP_IMU_TEMP_MAX 82.0f58#define AP_IMU_TEMP_OFFSET 2659// for home position related data60#define HOME_ALT_OFFSET 1261#define HOME_BEARING_LIMIT 0x7F62#define HOME_BEARING_OFFSET 2563// for velocity and yaw data64#define VELANDYAW_XYVEL_OFFSET 965#define VELANDYAW_YAW_LIMIT 0x7FF66#define VELANDYAW_YAW_OFFSET 1767#define VELANDYAW_ARSPD_OFFSET 2868// for attitude (roll, pitch) and range data69#define ATTIANDRNG_ROLL_LIMIT 0x7FF70#define ATTIANDRNG_PITCH_LIMIT 0x3FF71#define ATTIANDRNG_PITCH_OFFSET 1172#define ATTIANDRNG_RNGFND_OFFSET 2173// for terrain data74#define TERRAIN_UNHEALTHY_OFFSET 1375// for wind data76#define WIND_ANGLE_LIMIT 0x7F77#define WIND_SPEED_OFFSET 778#define WIND_APPARENT_ANGLE_OFFSET 1579#define WIND_APPARENT_SPEED_OFFSET 2280// for waypoint data81#define WP_NUMBER_LIMIT 204782#define WP_DISTANCE_LIMIT 102300083#define WP_DISTANCE_OFFSET 1184#define WP_BEARING_OFFSET 238586extern const AP_HAL::HAL& hal;8788AP_Frsky_SPort_Passthrough *AP_Frsky_SPort_Passthrough::singleton;8990bool AP_Frsky_SPort_Passthrough::init()91{92if (!AP_RCTelemetry::init()) {93return false;94}95return AP_Frsky_SPort::init();96}9798bool AP_Frsky_SPort_Passthrough::init_serial_port()99{100if (_use_external_data) {101return true;102}103return AP_Frsky_SPort::init_serial_port();104}105106void AP_Frsky_SPort_Passthrough::send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data)107{108if (_use_external_data) {109external_data.packet.frame = frame;110external_data.packet.appid = appid;111external_data.packet.data = data;112external_data.pending = true;113return;114}115116return AP_Frsky_SPort::send_sport_frame(frame, appid, data);117}118119/*120setup ready for passthrough telem121*/122void AP_Frsky_SPort_Passthrough::setup_wfq_scheduler(void)123{124// initialize packet weights for the WFQ scheduler125// priority[i] = 1/_scheduler.packet_weight[i]126// rate[i] = LinkRate * ( priority[i] / (sum(priority[1-n])) )127set_scheduler_entry(TEXT, 35, 28); // 0x5000 status text (dynamic)128set_scheduler_entry(ATTITUDE, 50, 38); // 0x5006 Attitude and range (dynamic)129set_scheduler_entry(GPS_LAT, 550, 280); // 0x800 GPS lat130set_scheduler_entry(GPS_LON, 550, 280); // 0x800 GPS lon131set_scheduler_entry(VEL_YAW, 400, 250); // 0x5005 Vel and Yaw132set_scheduler_entry(AP_STATUS, 700, 500); // 0x5001 AP status133set_scheduler_entry(GPS_STATUS, 700, 500); // 0x5002 GPS status134set_scheduler_entry(HOME, 400, 500); // 0x5004 Home135set_scheduler_entry(BATT_2, 1300, 500); // 0x5008 Battery 2 status136set_scheduler_entry(BATT_1, 1300, 500); // 0x5003 Battery 1 status137set_scheduler_entry(PARAM, 1700, 1000); // 0x5007 parameters138set_scheduler_entry(RPM, 300, 330); // 0x500A rpm sensors 1 and 2139set_scheduler_entry(TERRAIN, 700, 500); // 0x500B terrain data140set_scheduler_entry(WIND, 700, 500); // 0x500C wind data141set_scheduler_entry(WAYPOINT, 750, 500); // 0x500D waypoint data142set_scheduler_entry(UDATA, 5000, 200); // user data143144// initialize default sport sensor ID145set_sensor_id(_frsky_parameters->_dnlink_id, downlink_sensor_id);146#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL147set_scheduler_entry(MAV, 35, 25); // mavlite148// initialize sport sensor IDs149set_sensor_id(_frsky_parameters->_uplink_id, _SPort_bidir.uplink_sensor_id);150set_sensor_id(_frsky_parameters->_dnlink1_id, _SPort_bidir.downlink1_sensor_id);151set_sensor_id(_frsky_parameters->_dnlink2_id, _SPort_bidir.downlink2_sensor_id);152// initialize sport153hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Frsky_SPort_Passthrough::process_rx_queue, void));154#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL155}156157/*158dynamically change scheduler priorities based on queue sizes159*/160void AP_Frsky_SPort_Passthrough::adjust_packet_weight(bool queue_empty)161{162/*163When queues are empty set a low priority (high weight), when queues164are not empty set a higher priority (low weight) based on the following165relative priority order: mavlite > status text > attitude.166*/167#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL168if (!_SPort_bidir.tx_packet_queue.is_empty()) {169_scheduler.packet_weight[MAV] = 30; // mavlite170if (!queue_empty) {171_scheduler.packet_weight[TEXT] = 45; // messages172_scheduler.packet_weight[ATTITUDE] = 80; // attitude173} else {174_scheduler.packet_weight[TEXT] = 5000; // messages175_scheduler.packet_weight[ATTITUDE] = 80; // attitude176}177} else {178_scheduler.packet_weight[MAV] = 5000; // mavlite179if (!queue_empty) {180_scheduler.packet_weight[TEXT] = 45; // messages181_scheduler.packet_weight[ATTITUDE] = 80; // attitude182} else {183_scheduler.packet_weight[TEXT] = 5000; // messages184_scheduler.packet_weight[ATTITUDE] = 45; // attitude185}186}187#else //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL188if (!queue_empty) {189_scheduler.packet_weight[TEXT] = 45; // messages190_scheduler.packet_weight[ATTITUDE] = 80; // attitude191} else {192_scheduler.packet_weight[TEXT] = 5000; // messages193_scheduler.packet_weight[ATTITUDE] = 45; // attitude194}195#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL196// when using fport raise user data priority if any packets are pending197if (_use_external_data && _sport_push_buffer.pending) {198_scheduler.packet_weight[UDATA] = 250;199} else {200_scheduler.packet_weight[UDATA] = 5000; // user data201}202}203204// WFQ scheduler205bool AP_Frsky_SPort_Passthrough::is_packet_ready(uint8_t idx, bool queue_empty)206{207bool packet_ready = false;208switch (idx) {209case TEXT:210packet_ready = !queue_empty;211break;212case GPS_LAT:213case GPS_LON:214// force gps coords to use default sensor ID, always send when used with external data215packet_ready = _use_external_data || (_passthrough.new_byte == downlink_sensor_id);216break;217case AP_STATUS:218packet_ready = gcs().vehicle_initialised();219break;220case BATT_2:221packet_ready = AP::battery().num_instances() > 1;222break;223case RPM:224{225packet_ready = false;226#if AP_RPM_ENABLED227const AP_RPM *rpm = AP::rpm();228if (rpm == nullptr) {229break;230}231packet_ready = rpm->num_sensors() > 0;232#endif233}234break;235case TERRAIN:236{237packet_ready = false;238#if AP_TERRAIN_AVAILABLE239const AP_Terrain *terrain = AP::terrain();240packet_ready = terrain && terrain->enabled();241#endif242}243break;244case WIND:245#if !APM_BUILD_TYPE(APM_BUILD_Rover)246{247float a;248WITH_SEMAPHORE(AP::ahrs().get_semaphore());249if (AP::ahrs().airspeed_estimate_true(a)) {250// if we have an airspeed estimate then we have a valid wind estimate251packet_ready = true;252}253}254#else255{256const AP_WindVane* windvane = AP_WindVane::get_singleton();257packet_ready = windvane != nullptr && windvane->enabled();258}259#endif260break;261case WAYPOINT:262{263const AP_Mission *mission = AP::mission();264packet_ready = mission != nullptr && mission->get_current_nav_index() > 0;265}266break;267case UDATA:268// when using fport user data is sent by scheduler269// when using sport user data is sent responding to custom polling270packet_ready = _use_external_data && _sport_push_buffer.pending;271break;272#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL273case MAV:274packet_ready = !_SPort_bidir.tx_packet_queue.is_empty();275break;276#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL277default:278packet_ready = true;279break;280}281282return packet_ready;283}284285/*286* WFQ scheduler287* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)288*/289void AP_Frsky_SPort_Passthrough::process_packet(uint8_t idx)290{291// send packet292switch (idx) {293case TEXT: // 0x5000 status text294if (get_next_msg_chunk()) {295send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID, _msg_chunk.chunk);296}297break;298case ATTITUDE: // 0x5006 Attitude and range299send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+6, calc_attiandrng());300break;301case GPS_LAT: // 0x800 GPS lat302// sample both lat and lon at the same time303send_sport_frame(SPORT_DATA_FRAME, GPS_LONG_LATI_FIRST_ID, calc_gps_latlng(_passthrough.send_latitude)); // gps latitude or longitude304_passthrough.gps_lng_sample = calc_gps_latlng(_passthrough.send_latitude);305// force the scheduler to select GPS lon as packet that's been waiting the most306// this guarantees that lat and lon are sent as consecutive packets307_scheduler.packet_timer[GPS_LON] = _scheduler.packet_timer[GPS_LAT] - 10000;308break;309case GPS_LON: // 0x800 GPS lon310send_sport_frame(SPORT_DATA_FRAME, GPS_LONG_LATI_FIRST_ID, _passthrough.gps_lng_sample); // gps longitude311break;312case VEL_YAW: // 0x5005 Vel and Yaw313send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+5, calc_velandyaw());314break;315case AP_STATUS: // 0x5001 AP status316send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+1, calc_ap_status());317break;318case GPS_STATUS: // 0x5002 GPS Status319send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+2, calc_gps_status());320break;321case HOME: // 0x5004 Home322send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+4, calc_home());323break;324case BATT_2: // 0x5008 Battery 2 status325send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+8, calc_batt(1));326break;327case BATT_1: // 0x5003 Battery 1 status328send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+3, calc_batt(0));329break;330case PARAM: // 0x5007 parameters331send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+7, calc_param());332break;333case RPM: // 0x500A rpm sensors 1 and 2334send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0A, calc_rpm());335break;336case TERRAIN: // 0x500B terrain data337send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0B, calc_terrain());338break;339case WIND: // 0x500C terrain data340send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0C, calc_wind());341break;342case WAYPOINT: // 0x500D waypoint data343send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0D, calc_waypoint());344break;345case UDATA: // user data346{347WITH_SEMAPHORE(_sport_push_buffer.sem);348if (_use_external_data && _sport_push_buffer.pending) {349send_sport_frame(_sport_push_buffer.packet.frame, _sport_push_buffer.packet.appid, _sport_push_buffer.packet.data);350_sport_push_buffer.pending = false;351}352}353break;354#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL355case MAV: // mavlite356process_tx_queue();357break;358#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL359}360}361362/*363* send telemetry data364* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)365*/366void AP_Frsky_SPort_Passthrough::send(void)367{368const uint16_t numc = MIN(_port->available(), 1024U);369370// this is the constant for hub data frame371if (_port->txspace() < 19) {372return;373}374// keep only the last two bytes of the data found in the serial buffer, as we shouldn't respond to old poll requests375uint8_t prev_byte = 0;376for (uint16_t i = 0; i < numc; i++) {377prev_byte = _passthrough.new_byte;378_passthrough.new_byte = _port->read();379#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL380AP_Frsky_SPort::sport_packet_t sp;381382if (_sport_handler.process_byte(sp, _passthrough.new_byte)) {383queue_rx_packet(sp);384}385#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL386}387// check if we should respond to this polling byte388if (prev_byte == FRAME_HEAD) {389if (is_passthrough_byte(_passthrough.new_byte)) {390run_wfq_scheduler();391} else {392// respond to custom user data polling393WITH_SEMAPHORE(_sport_push_buffer.sem);394if (_sport_push_buffer.pending && _passthrough.new_byte == _sport_push_buffer.packet.sensor) {395send_sport_frame(_sport_push_buffer.packet.frame, _sport_push_buffer.packet.appid, _sport_push_buffer.packet.data);396_sport_push_buffer.pending = false;397}398}399}400}401402/*403* grabs one "chunk" (4 bytes) of the queued message to be transmitted404* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)405*/406bool AP_Frsky_SPort_Passthrough::get_next_msg_chunk(void)407{408if (!_statustext.available) {409WITH_SEMAPHORE(_statustext.sem);410if (!_statustext.queue.pop(_statustext.next)) {411return false;412}413_statustext.available = true;414}415416if (_msg_chunk.repeats == 0) { // if it's the first time get_next_msg_chunk is called for a given chunk417uint8_t character = 0;418_msg_chunk.chunk = 0; // clear the 4 bytes of the chunk buffer419420for (uint8_t i = 0; i < 4 && _msg_chunk.char_index < sizeof(_statustext.next.text); i++) {421character = _statustext.next.text[_msg_chunk.char_index++];422423if (!character) {424break;425}426427_msg_chunk.chunk |= character << (3-i) * 8;428}429430if (!character || (_msg_chunk.char_index == sizeof(_statustext.next.text))) { // we've reached the end of the message (string terminated by '\0' or last character of the string has been processed)431_msg_chunk.char_index = 0; // reset index to get ready to process the next message432// add severity which is sent as the MSB of the last three bytes of the last chunk (bits 24, 16, and 8) since a character is on 7 bits433_msg_chunk.chunk |= (_statustext.next.severity & 0x4)<<21;434_msg_chunk.chunk |= (_statustext.next.severity & 0x2)<<14;435_msg_chunk.chunk |= (_statustext.next.severity & 0x1)<<7;436}437}438439// repeat each message chunk 3 times to ensure transmission440// on slow links reduce the number of duplicate chunks441uint8_t extra_chunks = 2;442443if (_scheduler.avg_packet_rate < 20) {444// with 3 or more extra frsky sensors on the bus445// send messages only once446extra_chunks = 0;447} else if (_scheduler.avg_packet_rate < 30) {448// with 1 or 2 extra frsky sensors on the bus449// send messages twice450extra_chunks = 1;451}452453if (_msg_chunk.repeats++ > extra_chunks ) {454_msg_chunk.repeats = 0;455if (_msg_chunk.char_index == 0) {456// we're ready for the next message457_statustext.available = false;458}459}460return true;461}462463/*464* prepare parameter data465* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)466*/467uint32_t AP_Frsky_SPort_Passthrough::calc_param(void)468{469uint8_t param_id = _paramID; //cache it because it gets changed inside the switch470uint32_t param_value = 0;471472switch (_paramID) {473case NONE:474case FRAME_TYPE:475param_value = gcs().frame_type(); // see MAV_TYPE in Mavlink definition file common.h476_paramID = BATT_CAPACITY_1;477break;478case BATT_CAPACITY_1:479param_value = (uint32_t)roundf(AP::battery().pack_capacity_mah(0)); // battery pack capacity in mAh480_paramID = AP::battery().num_instances() > 1 ? BATT_CAPACITY_2 : TELEMETRY_FEATURES;481break;482case BATT_CAPACITY_2:483param_value = (uint32_t)roundf(AP::battery().pack_capacity_mah(1)); // battery pack capacity in mAh484_paramID = TELEMETRY_FEATURES;485break;486case TELEMETRY_FEATURES:487#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL488BIT_SET(param_value,PassthroughFeatures::BIDIR);489#endif490#if AP_SCRIPTING_ENABLED491BIT_SET(param_value,PassthroughFeatures::SCRIPTING);492#endif493_paramID = FRAME_TYPE;494break;495}496//Reserve first 8 bits for param ID, use other 24 bits to store parameter value497return (param_id << PARAM_ID_OFFSET) | (param_value & PARAM_VALUE_LIMIT);498}499500/*501* prepare gps status data502* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)503*/504uint32_t AP_Frsky_SPort_Passthrough::calc_gps_status(void)505{506const AP_GPS &gps = AP::gps();507508// number of GPS satellites visible (limit to 15 (0xF) since the value is stored on 4 bits)509uint32_t gps_status = (gps.num_sats() < GPS_SATS_LIMIT) ? gps.num_sats() : GPS_SATS_LIMIT;510// GPS receiver status (limit to 0-3 (0x3) since the value is stored on 2 bits: NO_GPS = 0, NO_FIX = 1, GPS_OK_FIX_2D = 2, GPS_OK_FIX_3D or GPS_OK_FIX_3D_DGPS or GPS_OK_FIX_3D_RTK_FLOAT or GPS_OK_FIX_3D_RTK_FIXED = 3)511gps_status |= ((gps.status() < GPS_STATUS_LIMIT) ? gps.status() : GPS_STATUS_LIMIT)<<GPS_STATUS_OFFSET;512// GPS horizontal dilution of precision in dm513gps_status |= prep_number(roundf(gps.get_hdop() * 0.1f),2,1)<<GPS_HDOP_OFFSET;514// GPS receiver advanced status (0: no advanced fix, 1: GPS_OK_FIX_3D_DGPS, 2: GPS_OK_FIX_3D_RTK_FLOAT, 3: GPS_OK_FIX_3D_RTK_FIXED)515gps_status |= ((gps.status() > GPS_STATUS_LIMIT) ? gps.status()-GPS_STATUS_LIMIT : 0)<<GPS_ADVSTATUS_OFFSET;516// Altitude MSL in dm517const Location &loc = gps.location();518gps_status |= prep_number(roundf(loc.alt * 0.1f),2,2)<<GPS_ALTMSL_OFFSET;519return gps_status;520}521522/*523* prepare battery data524* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)525*/526uint32_t AP_Frsky_SPort_Passthrough::calc_batt(uint8_t instance)527{528const AP_BattMonitor &_battery = AP::battery();529530float current, consumed_mah;531if (!_battery.current_amps(current, instance)) {532current = 0;533}534if (!_battery.consumed_mah(consumed_mah, instance)) {535consumed_mah = 0;536}537538// battery voltage in decivolts, can have up to a 12S battery (4.25Vx12S = 51.0V)539uint32_t batt = (((uint16_t)roundf(_battery.voltage(instance) * 10.0f)) & BATT_VOLTAGE_LIMIT);540// battery current draw in deciamps541batt |= prep_number(roundf(current * 10.0f), 2, 1)<<BATT_CURRENT_OFFSET;542// battery current drawn since power on in mAh (limit to 32767 (0x7FFF) since value is stored on 15 bits)543batt |= ((consumed_mah < BATT_TOTALMAH_LIMIT) ? ((uint16_t)roundf(consumed_mah) & BATT_TOTALMAH_LIMIT) : BATT_TOTALMAH_LIMIT)<<BATT_TOTALMAH_OFFSET;544return batt;545}546547/*548* true if we need to respond to the last polling byte549* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)550*/551bool AP_Frsky_SPort_Passthrough::is_passthrough_byte(const uint8_t byte) const552{553#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL554if( byte == _SPort_bidir.downlink1_sensor_id || byte == _SPort_bidir.downlink2_sensor_id ) {555return true;556}557#endif558return byte == downlink_sensor_id;559}560561/*562* prepare various autopilot status data563* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)564*/565uint32_t AP_Frsky_SPort_Passthrough::calc_ap_status(void)566{567// IMU temperature: offset -19, 0 means temp =< 19°, 63 means temp => 82°568uint8_t imu_temp = 0;569#if AP_INERTIALSENSOR_ENABLED570imu_temp = (uint8_t) roundf(constrain_float(AP::ins().get_temperature(0), AP_IMU_TEMP_MIN, AP_IMU_TEMP_MAX) - AP_IMU_TEMP_MIN);571#endif572573// control/flight mode number (limit to 31 (0x1F) since the value is stored on 5 bits)574uint32_t ap_status = (uint8_t)((gcs().custom_mode()+1) & AP_CONTROL_MODE_LIMIT);575// simple/super simple modes flags576ap_status |= (uint8_t)(gcs().simple_input_active())<<AP_SIMPLE_OFFSET;577ap_status |= (uint8_t)(gcs().supersimple_input_active())<<AP_SSIMPLE_OFFSET;578// is_flying flag579ap_status |= (uint8_t)(AP_Notify::flags.flying) << AP_FLYING_OFFSET;580// armed flag581ap_status |= (uint8_t)(AP_Notify::flags.armed)<<AP_ARMED_OFFSET;582// battery failsafe flag583ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery)<<AP_BATT_FS_OFFSET;584// bad ekf flag585ap_status |= (uint8_t)(AP_Notify::flags.ekf_bad)<<AP_EKF_FS_OFFSET;586// generic failsafe587ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery||AP_Notify::flags.failsafe_ekf||AP_Notify::flags.failsafe_gcs||AP_Notify::flags.failsafe_radio)<<AP_FS_OFFSET;588#if AP_FENCE_ENABLED589// fence status590AC_Fence *fence = AP::fence();591if (fence != nullptr) {592ap_status |= (uint8_t)(fence->enabled() && fence->present()) << AP_FENCE_PRESENT_OFFSET;593ap_status |= (uint8_t)(fence->get_breaches()>0) << AP_FENCE_BREACH_OFFSET;594}595#endif596// signed throttle [-100,100] scaled down to [-63,63] on 7 bits, MSB for sign + 6 bits for 0-63597ap_status |= prep_number(gcs().get_hud_throttle()*0.63, 2, 0)<<AP_THROTTLE_OFFSET;598// IMU temperature599ap_status |= imu_temp << AP_IMU_TEMP_OFFSET;600return ap_status;601}602603/*604* prepare home position related data605* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)606*/607uint32_t AP_Frsky_SPort_Passthrough::calc_home(void)608{609uint32_t home = 0;610Location loc;611Location home_loc;612bool got_position = false;613float _relative_home_altitude = 0;614615{616AP_AHRS &_ahrs = AP::ahrs();617WITH_SEMAPHORE(_ahrs.get_semaphore());618got_position = _ahrs.get_location(loc);619home_loc = _ahrs.get_home();620}621622if (got_position) {623// check home_loc is valid624if (home_loc.lat != 0 || home_loc.lng != 0) {625// distance between vehicle and home_loc in meters626home = prep_number(roundf(home_loc.get_distance(loc)), 3, 2);627// angle from front of vehicle to the direction of home_loc in 3 degree increments (just in case, limit to 127 (0x7F) since the value is stored on 7 bits)628home |= (((uint8_t)roundf(loc.get_bearing_to(home_loc) * 0.00333f)) & HOME_BEARING_LIMIT)<<HOME_BEARING_OFFSET;629}630// altitude between vehicle and home_loc631_relative_home_altitude = loc.alt;632if (!loc.relative_alt) {633// loc.alt has home altitude added, remove it634_relative_home_altitude -= home_loc.alt;635}636}637// altitude above home in decimeters638home |= prep_number(roundf(_relative_home_altitude * 0.1f), 3, 2)<<HOME_ALT_OFFSET;639return home;640}641642/*643* prepare velocity and yaw data644* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)645*/646uint32_t AP_Frsky_SPort_Passthrough::calc_velandyaw(void)647{648float vspd = AP_RCTelemetry::get_vspeed_ms();649// vertical velocity in dm/s650uint32_t velandyaw = prep_number(roundf(vspd * 10), 2, 1);651float airspeed_m; // m/s652float hspeed_m; // m/s653bool airspeed_estimate_true;654AP_AHRS &_ahrs = AP::ahrs();655{656WITH_SEMAPHORE(_ahrs.get_semaphore());657hspeed_m = _ahrs.groundspeed(); // default is to use groundspeed658airspeed_estimate_true = AP::ahrs().airspeed_estimate_true(airspeed_m);659}660bool option_airspeed_enabled = (_frsky_parameters->_options & frsky_options_e::OPTION_AIRSPEED_AND_GROUNDSPEED) != 0;661// airspeed estimate + airspeed option disabled (default) => send airspeed (we give priority to airspeed over groundspeed)662// airspeed estimate + airspeed option enabled => alternate airspeed/groundspeed, i.e send airspeed only when _passthrough.send_airspeed==true663if (airspeed_estimate_true && (!option_airspeed_enabled || _passthrough.send_airspeed)) {664hspeed_m = airspeed_m;665}666// horizontal velocity in dm/s667velandyaw |= prep_number(roundf(hspeed_m * 10), 2, 1)<<VELANDYAW_XYVEL_OFFSET;668// yaw from [0;36000] centidegrees to .2 degree increments [0;1800] (just in case, limit to 2047 (0x7FF) since the value is stored on 11 bits)669velandyaw |= ((uint16_t)roundf(_ahrs.yaw_sensor * 0.05f) & VELANDYAW_YAW_LIMIT)<<VELANDYAW_YAW_OFFSET;670// flag the airspeed bit if required671if (airspeed_estimate_true && option_airspeed_enabled && _passthrough.send_airspeed) {672velandyaw |= 1U<<VELANDYAW_ARSPD_OFFSET;673}674// toggle air/ground speed selector675_passthrough.send_airspeed = !_passthrough.send_airspeed;676return velandyaw;677}678679/*680* prepare attitude (roll, pitch) and range data681* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)682*/683uint32_t AP_Frsky_SPort_Passthrough::calc_attiandrng(void)684{685#if AP_RANGEFINDER_ENABLED686const RangeFinder *_rng = RangeFinder::get_singleton();687#endif688689float roll;690float pitch;691AP::vehicle()->get_osd_roll_pitch_rad(roll,pitch);692// roll from [-18000;18000] centidegrees to unsigned .2 degree increments [0;1800] (just in case, limit to 2047 (0x7FF) since the value is stored on 11 bits)693uint32_t attiandrng = ((uint16_t)roundf((roll * RAD_TO_DEG * 100 + 18000) * 0.05f) & ATTIANDRNG_ROLL_LIMIT);694// pitch from [-9000;9000] centidegrees to unsigned .2 degree increments [0;900] (just in case, limit to 1023 (0x3FF) since the value is stored on 10 bits)695attiandrng |= ((uint16_t)roundf((pitch * RAD_TO_DEG * 100 + 9000) * 0.05f) & ATTIANDRNG_PITCH_LIMIT)<<ATTIANDRNG_PITCH_OFFSET;696// rangefinder measurement in cm697#if AP_RANGEFINDER_ENABLED698attiandrng |= prep_number(_rng ? _rng->distance_cm_orient(ROTATION_PITCH_270) : 0, 3, 1)<<ATTIANDRNG_RNGFND_OFFSET;699#else700attiandrng |= prep_number(0, 3, 1)<<ATTIANDRNG_RNGFND_OFFSET;701#endif702return attiandrng;703}704705/*706* prepare rpm for sensors 1 and 2707* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)708*/709uint32_t AP_Frsky_SPort_Passthrough::calc_rpm(void)710{711#if AP_RPM_ENABLED712const AP_RPM *ap_rpm = AP::rpm();713if (ap_rpm == nullptr) {714return 0;715}716uint32_t value = 0;717// we send: rpm_value*0.1 as 16 bits signed718float rpm;719// bits 0-15 for rpm 0720if (ap_rpm->get_rpm(0,rpm)) {721value |= (int16_t)roundf(rpm * 0.1);722}723// bits 16-31 for rpm 1724if (ap_rpm->get_rpm(1,rpm)) {725value |= (int16_t)roundf(rpm * 0.1) << 16;726}727return value;728#else729return 0;730#endif731}732733/*734* prepare terrain data735* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)736*/737uint32_t AP_Frsky_SPort_Passthrough::calc_terrain(void)738{739uint32_t value = 0;740#if AP_TERRAIN_AVAILABLE741AP_Terrain *terrain = AP::terrain();742if (terrain == nullptr || !terrain->enabled()) {743return value;744}745float height_above_terrain;746if (terrain->height_above_terrain(height_above_terrain, true)) {747// vehicle height above terrain748value |= prep_number(roundf(height_above_terrain * 10), 3, 2);749}750// terrain unhealthy flag751value |= (uint8_t)(terrain->status() == AP_Terrain::TerrainStatus::TerrainStatusUnhealthy) << TERRAIN_UNHEALTHY_OFFSET;752#endif753return value;754}755756/*757* prepare wind data758* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)759* wind direction = 0 means North760*/761uint32_t AP_Frsky_SPort_Passthrough::calc_wind(void)762{763#if !APM_BUILD_TYPE(APM_BUILD_Rover)764Vector3f v;765{766AP_AHRS &ahrs = AP::ahrs();767WITH_SEMAPHORE(ahrs.get_semaphore());768v = ahrs.wind_estimate();769}770// wind angle in 3 degree increments 0,360 (unsigned)771uint32_t value = prep_number(roundf(wrap_360(degrees(atan2f(-v.y, -v.x))) * (1.0f/3.0f)), 2, 0);772// wind speed in dm/s773value |= prep_number(roundf(v.length() * 10), 2, 1) << WIND_SPEED_OFFSET;774#else775const AP_WindVane* windvane = AP_WindVane::get_singleton();776uint32_t value = 0;777if (windvane != nullptr && windvane->enabled()) {778// true wind angle in 3 degree increments 0,360 (unsigned)779value = prep_number(roundf(wrap_360(degrees(windvane->get_true_wind_direction_rad())) * (1.0f/3.0f)), 2, 0);780// true wind speed in dm/s781value |= prep_number(roundf(windvane->get_true_wind_speed() * 10), 2, 1) << WIND_SPEED_OFFSET;782// apparent wind angle in 3 degree increments -180,180 (signed)783value |= prep_number(roundf(degrees(windvane->get_apparent_wind_direction_rad()) * (1.0f/3.0f)), 2, 0) << WIND_APPARENT_ANGLE_OFFSET;784// apparent wind speed in dm/s785value |= prep_number(roundf(windvane->get_apparent_wind_speed() * 10), 2, 1) << WIND_APPARENT_SPEED_OFFSET;786}787#endif788return value;789}790/*791* prepare waypoint data792* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)793*/794uint32_t AP_Frsky_SPort_Passthrough::calc_waypoint(void)795{796const AP_Mission *mission = AP::mission();797const AP_Vehicle *vehicle = AP::vehicle();798if (mission == nullptr || vehicle == nullptr) {799return 0U;800}801float wp_distance;802if (!vehicle->get_wp_distance_m(wp_distance)) {803return 0U;804}805float angle;806if (!vehicle->get_wp_bearing_deg(angle)) {807return 0U;808}809// waypoint current nav index810uint32_t value = MIN(mission->get_current_nav_index(), WP_NUMBER_LIMIT);811// distance to next waypoint812value |= prep_number(wp_distance, 3, 2) << WP_DISTANCE_OFFSET;813// bearing encoded in 3 degrees increments814value |= ((uint8_t)roundf(wrap_360(angle) * 0.333f)) << WP_BEARING_OFFSET;815return value;816}817818/*819fetch Sport data for an external transport, such as FPort or crossfire820Note: we need to create a packet array with unique packet types821For very big frames we might have to relax the "unique packet type per frame"822constraint in order to maximize bandwidth usage823*/824bool AP_Frsky_SPort_Passthrough::get_telem_data(sport_packet_t* packet_array, uint8_t &packet_count, const uint8_t max_size)825{826if (!_use_external_data) {827return false;828}829830uint8_t idx = 0;831832// max_size >= WFQ_LAST_ITEM833// get a packet per enabled type834if (max_size >= WFQ_LAST_ITEM) {835for (uint8_t i=0; i<WFQ_LAST_ITEM; i++) {836if (process_scheduler_entry(i)) {837if (external_data.pending) {838packet_array[idx].frame = external_data.packet.frame;839packet_array[idx].appid = external_data.packet.appid;840packet_array[idx].data = external_data.packet.data;841idx++;842external_data.pending = false;843}844}845}846} else {847// max_size < WFQ_LAST_ITEM848// call run_wfq_scheduler(false) enough times to create a packet of up to max_size unique elements849uint32_t item_mask = 0;850for (uint8_t i=0; i<max_size; i++) {851// call the scheduler with the shaper "disabled"852const uint8_t item = run_wfq_scheduler(false);853if (!BIT_IS_SET(item_mask, item) && external_data.pending) {854// ok got some data, flip the bitmask bit to prevent adding the same packet type more than once855BIT_SET(item_mask, item);856packet_array[idx].frame = external_data.packet.frame;857packet_array[idx].appid = external_data.packet.appid;858packet_array[idx].data = external_data.packet.data;859idx++;860external_data.pending = false;861}862}863}864packet_count = idx;865return idx > 0;866}867868#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL869/*870allow external transports (e.g. FPort), to supply telemetry data871*/872bool AP_Frsky_SPort_Passthrough::set_telem_data(const uint8_t frame, const uint16_t appid, const uint32_t data)873{874// queue only Uplink packets875if (frame == SPORT_UPLINK_FRAME || frame == SPORT_UPLINK_FRAME_RW) {876const AP_Frsky_SPort::sport_packet_t sp {877{ 0x00, // this is ignored by process_sport_rx_queue() so no need for a real sensor ID878frame,879appid,880data }881};882883_SPort_bidir.rx_packet_queue.push_force(sp);884return true;885}886return false;887}888889/*890* Queue uplink packets in the sport rx queue891* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)892*/893void AP_Frsky_SPort_Passthrough::queue_rx_packet(const AP_Frsky_SPort::sport_packet_t packet)894{895// queue only Uplink packets896if (packet.sensor == _SPort_bidir.uplink_sensor_id && packet.frame == SPORT_UPLINK_FRAME) {897_SPort_bidir.rx_packet_queue.push_force(packet);898}899}900901/*902* Extract up to 1 mavlite message from the sport rx packet queue903* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)904*/905void AP_Frsky_SPort_Passthrough::process_rx_queue()906{907AP_Frsky_SPort::sport_packet_t packet;908uint8_t loop_count = 0; // prevent looping forever909while (_SPort_bidir.rx_packet_queue.pop(packet) && loop_count++ < MAVLITE_MSG_SPORT_PACKETS_COUNT(MAVLITE_MAX_PAYLOAD_LEN)) {910AP_Frsky_MAVlite_Message rxmsg;911912if (sport_to_mavlite.process(rxmsg, packet)) {913mavlite.process_message(rxmsg);914break; // process only 1 mavlite message each call915}916}917}918919/*920* Process the sport tx queue921* pop and send 1 sport packet922* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)923*/924void AP_Frsky_SPort_Passthrough::process_tx_queue()925{926AP_Frsky_SPort::sport_packet_t packet;927928if (!_SPort_bidir.tx_packet_queue.peek(packet)) {929return;930}931932// when using fport repeat each packet to account for933// fport packet loss (around 15%)934if (!_use_external_data || _SPort_bidir.tx_packet_duplicates++ == SPORT_TX_PACKET_DUPLICATES) {935_SPort_bidir.tx_packet_queue.pop();936_SPort_bidir.tx_packet_duplicates = 0;937}938939send_sport_frame(SPORT_DOWNLINK_FRAME, packet.appid, packet.data);940}941942/*943* Send a mavlite message944* Message is chunked in sport packets pushed in the tx queue945* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)946*/947bool AP_Frsky_SPort_Passthrough::send_message(const AP_Frsky_MAVlite_Message &txmsg)948{949return mavlite_to_sport.process(_SPort_bidir.tx_packet_queue, txmsg);950}951#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL952/*953* Utility method to apply constraints in changing sensor id values954* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)955*/956void AP_Frsky_SPort_Passthrough::set_sensor_id(AP_Int8 param_idx, uint8_t &sensor)957{958int8_t idx = param_idx.get();959960if (idx == -1) {961// disable this sensor962sensor = 0xFF;963return;964}965sensor = calc_sensor_id(idx);966}967968namespace AP969{970AP_Frsky_SPort_Passthrough *frsky_passthrough_telem()971{972return AP_Frsky_SPort_Passthrough::get_singleton();973}974};975976#endif // AP_FRSKY_SPORT_PASSTHROUGH_ENABLED977978979