Path: blob/master/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp
9754 views
#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{237#if AP_TERRAIN_AVAILABLE238const AP_Terrain *terrain = AP::terrain();239packet_ready = terrain && terrain->enabled();240#endif241}242break;243case WIND:244#if !APM_BUILD_TYPE(APM_BUILD_Rover)245{246float a;247WITH_SEMAPHORE(AP::ahrs().get_semaphore());248if (AP::ahrs().airspeed_TAS(a)) {249// if we have an airspeed estimate then we have a valid wind estimate250packet_ready = true;251}252}253#else254{255const AP_WindVane* windvane = AP_WindVane::get_singleton();256packet_ready = windvane != nullptr && windvane->enabled();257}258#endif259break;260case WAYPOINT:261{262const AP_Mission *mission = AP::mission();263packet_ready = mission != nullptr && mission->get_current_nav_index() > 0;264}265break;266case UDATA:267// when using fport user data is sent by scheduler268// when using sport user data is sent responding to custom polling269packet_ready = _use_external_data && _sport_push_buffer.pending;270break;271#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL272case MAV:273packet_ready = !_SPort_bidir.tx_packet_queue.is_empty();274break;275#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL276default:277packet_ready = true;278break;279}280281return packet_ready;282}283284/*285* WFQ scheduler286* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)287*/288void AP_Frsky_SPort_Passthrough::process_packet(uint8_t idx)289{290// send packet291switch (idx) {292case TEXT: // 0x5000 status text293if (get_next_msg_chunk()) {294send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID, _msg_chunk.chunk);295}296break;297case ATTITUDE: // 0x5006 Attitude and range298send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+6, calc_attiandrng());299break;300case GPS_LAT: // 0x800 GPS lat301// sample both lat and lon at the same time302send_sport_frame(SPORT_DATA_FRAME, GPS_LONG_LATI_FIRST_ID, calc_gps_latlng(_passthrough.send_latitude)); // gps latitude or longitude303_passthrough.gps_lng_sample = calc_gps_latlng(_passthrough.send_latitude);304// force the scheduler to select GPS lon as packet that's been waiting the most305// this guarantees that lat and lon are sent as consecutive packets306_scheduler.packet_timer[GPS_LON] = _scheduler.packet_timer[GPS_LAT] - 10000;307break;308case GPS_LON: // 0x800 GPS lon309send_sport_frame(SPORT_DATA_FRAME, GPS_LONG_LATI_FIRST_ID, _passthrough.gps_lng_sample); // gps longitude310break;311case VEL_YAW: // 0x5005 Vel and Yaw312send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+5, calc_velandyaw());313break;314case AP_STATUS: // 0x5001 AP status315send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+1, calc_ap_status());316break;317case GPS_STATUS: // 0x5002 GPS Status318send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+2, calc_gps_status());319break;320case HOME: // 0x5004 Home321send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+4, calc_home());322break;323case BATT_2: // 0x5008 Battery 2 status324send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+8, calc_batt(1));325break;326case BATT_1: // 0x5003 Battery 1 status327send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+3, calc_batt(0));328break;329case PARAM: // 0x5007 parameters330send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+7, calc_param());331break;332case RPM: // 0x500A rpm sensors 1 and 2333send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0A, calc_rpm());334break;335case TERRAIN: // 0x500B terrain data336send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0B, calc_terrain());337break;338case WIND: // 0x500C terrain data339send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0C, calc_wind());340break;341case WAYPOINT: // 0x500D waypoint data342send_sport_frame(SPORT_DATA_FRAME, DIY_FIRST_ID+0x0D, calc_waypoint());343break;344case UDATA: // user data345{346WITH_SEMAPHORE(_sport_push_buffer.sem);347if (_use_external_data && _sport_push_buffer.pending) {348send_sport_frame(_sport_push_buffer.packet.frame, _sport_push_buffer.packet.appid, _sport_push_buffer.packet.data);349_sport_push_buffer.pending = false;350}351}352break;353#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL354case MAV: // mavlite355process_tx_queue();356break;357#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL358}359}360361/*362* send telemetry data363* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)364*/365void AP_Frsky_SPort_Passthrough::send(void)366{367const uint16_t numc = MIN(_port->available(), 1024U);368369// this is the constant for hub data frame370if (_port->txspace() < 19) {371return;372}373// keep only the last two bytes of the data found in the serial buffer, as we shouldn't respond to old poll requests374uint8_t prev_byte = 0;375for (uint16_t i = 0; i < numc; i++) {376prev_byte = _passthrough.new_byte;377_passthrough.new_byte = _port->read();378#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL379AP_Frsky_SPort::sport_packet_t sp;380381if (_sport_handler.process_byte(sp, _passthrough.new_byte)) {382queue_rx_packet(sp);383}384#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL385}386// check if we should respond to this polling byte387if (prev_byte == FRAME_HEAD) {388if (is_passthrough_byte(_passthrough.new_byte)) {389run_wfq_scheduler();390} else {391// respond to custom user data polling392WITH_SEMAPHORE(_sport_push_buffer.sem);393if (_sport_push_buffer.pending && _passthrough.new_byte == _sport_push_buffer.packet.sensor) {394send_sport_frame(_sport_push_buffer.packet.frame, _sport_push_buffer.packet.appid, _sport_push_buffer.packet.data);395_sport_push_buffer.pending = false;396}397}398}399}400401/*402* grabs one "chunk" (4 bytes) of the queued message to be transmitted403* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)404*/405bool AP_Frsky_SPort_Passthrough::get_next_msg_chunk(void)406{407if (!_statustext.available) {408WITH_SEMAPHORE(_statustext.sem);409if (!_statustext.queue.pop(_statustext.next)) {410return false;411}412_statustext.available = true;413}414415if (_msg_chunk.repeats == 0) { // if it's the first time get_next_msg_chunk is called for a given chunk416uint8_t character = 0;417_msg_chunk.chunk = 0; // clear the 4 bytes of the chunk buffer418419for (uint8_t i = 0; i < 4 && _msg_chunk.char_index < sizeof(_statustext.next.text); i++) {420character = _statustext.next.text[_msg_chunk.char_index++];421422if (!character) {423break;424}425426_msg_chunk.chunk |= character << (3-i) * 8;427}428429if (!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)430_msg_chunk.char_index = 0; // reset index to get ready to process the next message431// 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 bits432_msg_chunk.chunk |= (_statustext.next.severity & 0x4)<<21;433_msg_chunk.chunk |= (_statustext.next.severity & 0x2)<<14;434_msg_chunk.chunk |= (_statustext.next.severity & 0x1)<<7;435}436}437438// repeat each message chunk 3 times to ensure transmission439// on slow links reduce the number of duplicate chunks440uint8_t extra_chunks = 2;441442if (_scheduler.avg_packet_rate < 20) {443// with 3 or more extra frsky sensors on the bus444// send messages only once445extra_chunks = 0;446} else if (_scheduler.avg_packet_rate < 30) {447// with 1 or 2 extra frsky sensors on the bus448// send messages twice449extra_chunks = 1;450}451452if (_msg_chunk.repeats++ > extra_chunks ) {453_msg_chunk.repeats = 0;454if (_msg_chunk.char_index == 0) {455// we're ready for the next message456_statustext.available = false;457}458}459return true;460}461462/*463* prepare parameter data464* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)465*/466uint32_t AP_Frsky_SPort_Passthrough::calc_param(void)467{468uint8_t param_id = _paramID; //cache it because it gets changed inside the switch469uint32_t param_value = 0;470471switch (_paramID) {472case NONE:473case FRAME_TYPE:474param_value = gcs().frame_type(); // see MAV_TYPE in Mavlink definition file common.h475_paramID = BATT_CAPACITY_1;476break;477case BATT_CAPACITY_1:478param_value = (uint32_t)roundf(AP::battery().pack_capacity_mah(0)); // battery pack capacity in mAh479_paramID = AP::battery().num_instances() > 1 ? BATT_CAPACITY_2 : TELEMETRY_FEATURES;480break;481case BATT_CAPACITY_2:482param_value = (uint32_t)roundf(AP::battery().pack_capacity_mah(1)); // battery pack capacity in mAh483_paramID = TELEMETRY_FEATURES;484break;485case TELEMETRY_FEATURES:486#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL487BIT_SET(param_value,PassthroughFeatures::BIDIR);488#endif489#if AP_SCRIPTING_ENABLED490BIT_SET(param_value,PassthroughFeatures::SCRIPTING);491#endif492_paramID = FRAME_TYPE;493break;494}495//Reserve first 8 bits for param ID, use other 24 bits to store parameter value496return (param_id << PARAM_ID_OFFSET) | (param_value & PARAM_VALUE_LIMIT);497}498499/*500* prepare gps status data501* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)502*/503uint32_t AP_Frsky_SPort_Passthrough::calc_gps_status(void)504{505const AP_GPS &gps = AP::gps();506507// number of GPS satellites visible (limit to 15 (0xF) since the value is stored on 4 bits)508uint32_t gps_status = (gps.num_sats() < GPS_SATS_LIMIT) ? gps.num_sats() : GPS_SATS_LIMIT;509// 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)510gps_status |= ((gps.status() < GPS_STATUS_LIMIT) ? gps.status() : GPS_STATUS_LIMIT)<<GPS_STATUS_OFFSET;511// GPS horizontal dilution of precision in dm512gps_status |= prep_number(roundf(gps.get_hdop() * 0.1f),2,1)<<GPS_HDOP_OFFSET;513// 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)514gps_status |= ((gps.status() > GPS_STATUS_LIMIT) ? gps.status()-GPS_STATUS_LIMIT : 0)<<GPS_ADVSTATUS_OFFSET;515// Altitude MSL in dm516const Location &loc = gps.location();517gps_status |= prep_number(roundf(loc.alt * 0.1f),2,2)<<GPS_ALTMSL_OFFSET;518return gps_status;519}520521/*522* prepare battery data523* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)524*/525uint32_t AP_Frsky_SPort_Passthrough::calc_batt(uint8_t instance)526{527const AP_BattMonitor &_battery = AP::battery();528529float current, consumed_mah;530if (!_battery.current_amps(current, instance)) {531current = 0;532}533if (!_battery.consumed_mah(consumed_mah, instance)) {534consumed_mah = 0;535}536537// battery voltage in decivolts, can have up to a 12S battery (4.25Vx12S = 51.0V)538uint32_t batt = (((uint16_t)roundf(_battery.voltage(instance) * 10.0f)) & BATT_VOLTAGE_LIMIT);539// battery current draw in deciamps540batt |= prep_number(roundf(current * 10.0f), 2, 1)<<BATT_CURRENT_OFFSET;541// battery current drawn since power on in mAh (limit to 32767 (0x7FFF) since value is stored on 15 bits)542batt |= ((consumed_mah < BATT_TOTALMAH_LIMIT) ? ((uint16_t)roundf(consumed_mah) & BATT_TOTALMAH_LIMIT) : BATT_TOTALMAH_LIMIT)<<BATT_TOTALMAH_OFFSET;543return batt;544}545546/*547* true if we need to respond to the last polling byte548* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)549*/550bool AP_Frsky_SPort_Passthrough::is_passthrough_byte(const uint8_t byte) const551{552#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL553if( byte == _SPort_bidir.downlink1_sensor_id || byte == _SPort_bidir.downlink2_sensor_id ) {554return true;555}556#endif557return byte == downlink_sensor_id;558}559560/*561* prepare various autopilot status data562* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)563*/564uint32_t AP_Frsky_SPort_Passthrough::calc_ap_status(void)565{566// IMU temperature: offset -19, 0 means temp =< 19°, 63 means temp => 82°567uint8_t imu_temp = 0;568#if AP_INERTIALSENSOR_ENABLED569imu_temp = (uint8_t) roundf(constrain_float(AP::ins().get_temperature(0), AP_IMU_TEMP_MIN, AP_IMU_TEMP_MAX) - AP_IMU_TEMP_MIN);570#endif571572// control/flight mode number (limit to 31 (0x1F) since the value is stored on 5 bits)573uint32_t ap_status = (uint8_t)((gcs().custom_mode()+1) & AP_CONTROL_MODE_LIMIT);574// simple/super simple modes flags575ap_status |= (uint8_t)(gcs().simple_input_active())<<AP_SIMPLE_OFFSET;576ap_status |= (uint8_t)(gcs().supersimple_input_active())<<AP_SSIMPLE_OFFSET;577// is_flying flag578ap_status |= (uint8_t)(AP_Notify::flags.flying) << AP_FLYING_OFFSET;579// armed flag580ap_status |= (uint8_t)(AP_Notify::flags.armed)<<AP_ARMED_OFFSET;581// battery failsafe flag582ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery)<<AP_BATT_FS_OFFSET;583// bad ekf flag584ap_status |= (uint8_t)(AP_Notify::flags.ekf_bad)<<AP_EKF_FS_OFFSET;585// generic failsafe586ap_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;587#if AP_FENCE_ENABLED588// fence status589AC_Fence *fence = AP::fence();590if (fence != nullptr) {591ap_status |= (uint8_t)(fence->enabled() && fence->present()) << AP_FENCE_PRESENT_OFFSET;592ap_status |= (uint8_t)(fence->get_breaches()>0) << AP_FENCE_BREACH_OFFSET;593}594#endif595// signed throttle [-100,100] scaled down to [-63,63] on 7 bits, MSB for sign + 6 bits for 0-63596ap_status |= prep_number(gcs().get_hud_throttle()*0.63, 2, 0)<<AP_THROTTLE_OFFSET;597// IMU temperature598ap_status |= imu_temp << AP_IMU_TEMP_OFFSET;599return ap_status;600}601602/*603* prepare home position related data604* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)605*/606uint32_t AP_Frsky_SPort_Passthrough::calc_home(void)607{608uint32_t home = 0;609Location loc;610Location home_loc;611bool got_position = false;612float _relative_home_altitude = 0;613614{615AP_AHRS &_ahrs = AP::ahrs();616WITH_SEMAPHORE(_ahrs.get_semaphore());617got_position = _ahrs.get_location(loc);618home_loc = _ahrs.get_home();619}620621if (got_position) {622// check home_loc is valid623if (home_loc.lat != 0 || home_loc.lng != 0) {624// distance between vehicle and home_loc in meters625home = prep_number(roundf(home_loc.get_distance(loc)), 3, 2);626// 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)627home |= (((uint8_t)roundf(loc.get_bearing_to(home_loc) * 0.00333f)) & HOME_BEARING_LIMIT)<<HOME_BEARING_OFFSET;628}629// altitude between vehicle and home_loc630_relative_home_altitude = loc.alt;631if (!loc.relative_alt) {632// loc.alt has home altitude added, remove it633_relative_home_altitude -= home_loc.alt;634}635}636// altitude above home in decimeters637home |= prep_number(roundf(_relative_home_altitude * 0.1f), 3, 2)<<HOME_ALT_OFFSET;638return home;639}640641/*642* prepare velocity and yaw data643* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)644*/645uint32_t AP_Frsky_SPort_Passthrough::calc_velandyaw(void)646{647float vspd = AP_RCTelemetry::get_vspeed_ms();648// vertical velocity in dm/s649uint32_t velandyaw = prep_number(roundf(vspd * 10), 2, 1);650float airspeed_m; // m/s651float hspeed_m; // m/s652bool airspeed_estimate_true;653AP_AHRS &_ahrs = AP::ahrs();654{655WITH_SEMAPHORE(_ahrs.get_semaphore());656hspeed_m = _ahrs.groundspeed(); // default is to use groundspeed657airspeed_estimate_true = AP::ahrs().airspeed_TAS(airspeed_m);658}659bool option_airspeed_enabled = (_frsky_parameters->_options & frsky_options_e::OPTION_AIRSPEED_AND_GROUNDSPEED) != 0;660// airspeed estimate + airspeed option disabled (default) => send airspeed (we give priority to airspeed over groundspeed)661// airspeed estimate + airspeed option enabled => alternate airspeed/groundspeed, i.e send airspeed only when _passthrough.send_airspeed==true662if (airspeed_estimate_true && (!option_airspeed_enabled || _passthrough.send_airspeed)) {663hspeed_m = airspeed_m;664}665// horizontal velocity in dm/s666velandyaw |= prep_number(roundf(hspeed_m * 10), 2, 1)<<VELANDYAW_XYVEL_OFFSET;667// yaw from [0;36000] centidegrees to 0.2 degree increments [0;1800] (just in case, limit to 2047 (0x7FF) since the value is stored on 11 bits)668velandyaw |= ((uint16_t)roundf(_ahrs.yaw_sensor * 0.05f) & VELANDYAW_YAW_LIMIT)<<VELANDYAW_YAW_OFFSET;669// flag the airspeed bit if required670if (airspeed_estimate_true && option_airspeed_enabled && _passthrough.send_airspeed) {671velandyaw |= 1U<<VELANDYAW_ARSPD_OFFSET;672}673// toggle air/ground speed selector674_passthrough.send_airspeed = !_passthrough.send_airspeed;675return velandyaw;676}677678/*679* prepare attitude (roll, pitch) and range data680* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)681*/682uint32_t AP_Frsky_SPort_Passthrough::calc_attiandrng(void)683{684#if AP_RANGEFINDER_ENABLED685const RangeFinder *_rng = RangeFinder::get_singleton();686#endif687688float roll;689float pitch;690AP::vehicle()->get_osd_roll_pitch_rad(roll,pitch);691// roll from [-18000;18000] centidegrees to unsigned 0.2 degree increments [0;1800] (just in case, limit to 2047 (0x7FF) since the value is stored on 11 bits)692uint32_t attiandrng = ((uint16_t)roundf((roll * RAD_TO_DEG * 100 + 18000) * 0.05f) & ATTIANDRNG_ROLL_LIMIT);693// pitch from [-9000;9000] centidegrees to unsigned 0.2 degree increments [0;900] (just in case, limit to 1023 (0x3FF) since the value is stored on 10 bits)694attiandrng |= ((uint16_t)roundf((pitch * RAD_TO_DEG * 100 + 9000) * 0.05f) & ATTIANDRNG_PITCH_LIMIT)<<ATTIANDRNG_PITCH_OFFSET;695// rangefinder measurement in cm696#if AP_RANGEFINDER_ENABLED697attiandrng |= prep_number(_rng ? _rng->distance_orient(ROTATION_PITCH_270)*100 : 0, 3, 1)<<ATTIANDRNG_RNGFND_OFFSET;698#else699attiandrng |= prep_number(0, 3, 1)<<ATTIANDRNG_RNGFND_OFFSET;700#endif701return attiandrng;702}703704/*705* prepare rpm for sensors 1 and 2706* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)707*/708uint32_t AP_Frsky_SPort_Passthrough::calc_rpm(void)709{710#if AP_RPM_ENABLED711const AP_RPM *ap_rpm = AP::rpm();712if (ap_rpm == nullptr) {713return 0;714}715uint32_t value = 0;716// we send: rpm_value*0.1 as 16 bits signed717float rpm;718// bits 0-15 for rpm 0719if (ap_rpm->get_rpm(0,rpm)) {720value |= (int16_t)roundf(rpm * 0.1);721}722// bits 16-31 for rpm 1723if (ap_rpm->get_rpm(1,rpm)) {724value |= (int16_t)roundf(rpm * 0.1) << 16;725}726return value;727#else728return 0;729#endif730}731732/*733* prepare terrain data734* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)735*/736uint32_t AP_Frsky_SPort_Passthrough::calc_terrain(void)737{738uint32_t value = 0;739#if AP_TERRAIN_AVAILABLE740AP_Terrain *terrain = AP::terrain();741if (terrain == nullptr || !terrain->enabled()) {742return value;743}744float height_above_terrain;745if (terrain->height_above_terrain(height_above_terrain, true)) {746// vehicle height above terrain747value |= prep_number(roundf(height_above_terrain * 10), 3, 2);748}749// terrain unhealthy flag750value |= (uint8_t)(terrain->status() == AP_Terrain::TerrainStatus::TerrainStatusUnhealthy) << TERRAIN_UNHEALTHY_OFFSET;751#endif752return value;753}754755/*756* prepare wind data757* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)758* wind direction = 0 means North759*/760uint32_t AP_Frsky_SPort_Passthrough::calc_wind(void)761{762#if !APM_BUILD_TYPE(APM_BUILD_Rover)763Vector3f v;764{765AP_AHRS &ahrs = AP::ahrs();766WITH_SEMAPHORE(ahrs.get_semaphore());767v = ahrs.wind_estimate();768}769// wind angle in 3 degree increments 0,360 (unsigned)770uint32_t value = prep_number(roundf(wrap_360(degrees(atan2f(-v.y, -v.x))) * (1.0f/3.0f)), 2, 0);771// wind speed in dm/s772value |= prep_number(roundf(v.length() * 10), 2, 1) << WIND_SPEED_OFFSET;773#else774const AP_WindVane* windvane = AP_WindVane::get_singleton();775uint32_t value = 0;776if (windvane != nullptr && windvane->enabled()) {777// true wind angle in 3 degree increments 0,360 (unsigned)778value = prep_number(roundf(wrap_360(degrees(windvane->get_true_wind_direction_rad())) * (1.0f/3.0f)), 2, 0);779// true wind speed in dm/s780value |= prep_number(roundf(windvane->get_true_wind_speed() * 10), 2, 1) << WIND_SPEED_OFFSET;781// apparent wind angle in 3 degree increments -180,180 (signed)782value |= prep_number(roundf(degrees(windvane->get_apparent_wind_direction_rad()) * (1.0f/3.0f)), 2, 0) << WIND_APPARENT_ANGLE_OFFSET;783// apparent wind speed in dm/s784value |= prep_number(roundf(windvane->get_apparent_wind_speed() * 10), 2, 1) << WIND_APPARENT_SPEED_OFFSET;785}786#endif787return value;788}789/*790* prepare waypoint data791* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)792*/793uint32_t AP_Frsky_SPort_Passthrough::calc_waypoint(void)794{795const AP_Mission *mission = AP::mission();796const AP_Vehicle *vehicle = AP::vehicle();797if (mission == nullptr || vehicle == nullptr) {798return 0U;799}800float wp_distance;801if (!vehicle->get_wp_distance_m(wp_distance)) {802return 0U;803}804float angle;805if (!vehicle->get_wp_bearing_deg(angle)) {806return 0U;807}808// waypoint current nav index809uint32_t value = MIN(mission->get_current_nav_index(), WP_NUMBER_LIMIT);810// distance to next waypoint811value |= prep_number(wp_distance, 3, 2) << WP_DISTANCE_OFFSET;812// bearing encoded in 3 degrees increments813value |= ((uint8_t)roundf(wrap_360(angle) * 0.333f)) << WP_BEARING_OFFSET;814return value;815}816817/*818fetch Sport data for an external transport, such as FPort or crossfire819Note: we need to create a packet array with unique packet types820For very big frames we might have to relax the "unique packet type per frame"821constraint in order to maximize bandwidth usage822*/823bool AP_Frsky_SPort_Passthrough::get_telem_data(sport_packet_t* packet_array, uint8_t &packet_count, const uint8_t max_size)824{825if (!_use_external_data) {826return false;827}828829uint8_t idx = 0;830831// max_size >= WFQ_LAST_ITEM832// get a packet per enabled type833if (max_size >= WFQ_LAST_ITEM) {834for (uint8_t i=0; i<WFQ_LAST_ITEM; i++) {835if (process_scheduler_entry(i)) {836if (external_data.pending) {837packet_array[idx].frame = external_data.packet.frame;838packet_array[idx].appid = external_data.packet.appid;839packet_array[idx].data = external_data.packet.data;840idx++;841external_data.pending = false;842}843}844}845} else {846// max_size < WFQ_LAST_ITEM847// call run_wfq_scheduler(false) enough times to create a packet of up to max_size unique elements848uint32_t item_mask = 0;849for (uint8_t i=0; i<max_size; i++) {850// call the scheduler with the shaper "disabled"851const uint8_t item = run_wfq_scheduler(false);852if (!BIT_IS_SET(item_mask, item) && external_data.pending) {853// ok got some data, flip the bitmask bit to prevent adding the same packet type more than once854BIT_SET(item_mask, item);855packet_array[idx].frame = external_data.packet.frame;856packet_array[idx].appid = external_data.packet.appid;857packet_array[idx].data = external_data.packet.data;858idx++;859external_data.pending = false;860}861}862}863packet_count = idx;864return idx > 0;865}866867#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL868/*869allow external transports (e.g. FPort), to supply telemetry data870*/871bool AP_Frsky_SPort_Passthrough::set_telem_data(const uint8_t frame, const uint16_t appid, const uint32_t data)872{873// queue only Uplink packets874if (frame == SPORT_UPLINK_FRAME || frame == SPORT_UPLINK_FRAME_RW) {875const AP_Frsky_SPort::sport_packet_t sp {876{ 0x00, // this is ignored by process_sport_rx_queue() so no need for a real sensor ID877frame,878appid,879data }880};881882_SPort_bidir.rx_packet_queue.push_force(sp);883return true;884}885return false;886}887888/*889* Queue uplink packets in the sport rx queue890* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)891*/892void AP_Frsky_SPort_Passthrough::queue_rx_packet(const AP_Frsky_SPort::sport_packet_t packet)893{894// queue only Uplink packets895if (packet.sensor == _SPort_bidir.uplink_sensor_id && packet.frame == SPORT_UPLINK_FRAME) {896_SPort_bidir.rx_packet_queue.push_force(packet);897}898}899900/*901* Extract up to 1 mavlite message from the sport rx packet queue902* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)903*/904void AP_Frsky_SPort_Passthrough::process_rx_queue()905{906AP_Frsky_SPort::sport_packet_t packet;907uint8_t loop_count = 0; // prevent looping forever908while (_SPort_bidir.rx_packet_queue.pop(packet) && loop_count++ < MAVLITE_MSG_SPORT_PACKETS_COUNT(MAVLITE_MAX_PAYLOAD_LEN)) {909AP_Frsky_MAVlite_Message rxmsg;910911if (sport_to_mavlite.process(rxmsg, packet)) {912mavlite.process_message(rxmsg);913break; // process only 1 mavlite message each call914}915}916}917918/*919* Process the sport tx queue920* pop and send 1 sport packet921* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)922*/923void AP_Frsky_SPort_Passthrough::process_tx_queue()924{925AP_Frsky_SPort::sport_packet_t packet;926927if (!_SPort_bidir.tx_packet_queue.peek(packet)) {928return;929}930931// when using fport repeat each packet to account for932// fport packet loss (around 15%)933if (!_use_external_data || _SPort_bidir.tx_packet_duplicates++ == SPORT_TX_PACKET_DUPLICATES) {934_SPort_bidir.tx_packet_queue.pop();935_SPort_bidir.tx_packet_duplicates = 0;936}937938send_sport_frame(SPORT_DOWNLINK_FRAME, packet.appid, packet.data);939}940941/*942* Send a mavlite message943* Message is chunked in sport packets pushed in the tx queue944* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)945*/946bool AP_Frsky_SPort_Passthrough::send_message(const AP_Frsky_MAVlite_Message &txmsg)947{948return mavlite_to_sport.process(_SPort_bidir.tx_packet_queue, txmsg);949}950#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL951/*952* Utility method to apply constraints in changing sensor id values953* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)954*/955void AP_Frsky_SPort_Passthrough::set_sensor_id(AP_Int8 param_idx, uint8_t &sensor)956{957int8_t idx = param_idx.get();958959if (idx == -1) {960// disable this sensor961sensor = 0xFF;962return;963}964sensor = calc_sensor_id(idx);965}966967namespace AP968{969AP_Frsky_SPort_Passthrough *frsky_passthrough_telem()970{971return AP_Frsky_SPort_Passthrough::get_singleton();972}973};974975#endif // AP_FRSKY_SPORT_PASSTHROUGH_ENABLED976977978