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/Tools/AP_Periph/msp.cpp
Views: 1798
/*1output MSP protocol from AP_Periph for ArduPilot and INAV2Thanks to input from Konstantin Sharlaimov3*/45#include <AP_HAL/AP_HAL_Boards.h>6#include "AP_Periph.h"78#ifdef HAL_PERIPH_ENABLE_MSP910void AP_Periph_FW::msp_init(AP_HAL::UARTDriver *_uart)11{12if (_uart) {13msp.port.uart = _uart;14msp.port.msp_version = MSP::MSP_V2_NATIVE;15_uart->begin(115200, 512, 512);16}17}181920/*21send a MSP packet22*/23void AP_Periph_FW::send_msp_packet(uint16_t cmd, void *p, uint16_t size)24{25uint8_t out_buf[size+16] {};26MSP::msp_packet_t pkt = {27.buf = { .ptr = out_buf, .end = MSP_ARRAYEND(out_buf), },28.cmd = (int16_t)cmd,29.flags = 0,30.result = 0,31};3233sbuf_write_data(&pkt.buf, p, size);34sbuf_switch_to_reader(&pkt.buf, &out_buf[0]);3536MSP::msp_serial_encode(&msp.port, &pkt, MSP::MSP_V2_NATIVE, true);37}3839/*40update MSP sensors41*/42void AP_Periph_FW::msp_sensor_update(void)43{44if (msp.port.uart == nullptr) {45return;46}47#ifdef HAL_PERIPH_ENABLE_GPS48send_msp_GPS();49#endif50#ifdef HAL_PERIPH_ENABLE_BARO51send_msp_baro();52#endif53#ifdef HAL_PERIPH_ENABLE_MAG54send_msp_compass();55#endif56#ifdef HAL_PERIPH_ENABLE_AIRSPEED57send_msp_airspeed();58#endif59}606162#ifdef HAL_PERIPH_ENABLE_GPS63/*64send MSP GPS packet65*/66void AP_Periph_FW::send_msp_GPS(void)67{68MSP::msp_gps_data_message_t p;6970if (gps.get_type(0) == AP_GPS::GPS_Type::GPS_TYPE_NONE) {71return;72}73if (msp.last_gps_ms == gps.last_message_time_ms(0)) {74return;75}76msp.last_gps_ms = gps.last_message_time_ms(0);7778const Location &loc = gps.location(0);79const Vector3f &vel = gps.velocity(0);8081p.instance = 0;82p.gps_week = gps.time_week(0);83p.ms_tow = gps.get_itow(0);84p.fix_type = uint8_t(gps.status(0));85p.satellites_in_view = gps.num_sats(0);8687float hacc=0, vacc=0, sacc=0;88gps.horizontal_accuracy(0, hacc);89gps.vertical_accuracy(0, vacc);90gps.speed_accuracy(0, sacc);9192p.horizontal_vel_accuracy = sacc*100;93p.horizontal_pos_accuracy = hacc*100;94p.vertical_pos_accuracy = vacc*100;95p.hdop = gps.get_hdop(0);96p.longitude = loc.lng;97p.latitude = loc.lat;98p.msl_altitude = loc.alt;99p.ned_vel_north = vel.x*100;100p.ned_vel_east = vel.y*100;101p.ned_vel_down = vel.z*100;102p.ground_course = wrap_360_cd(gps.ground_course(0)*100);103float yaw_deg=0, acc;104uint32_t time_ms;105if (gps.gps_yaw_deg(0, yaw_deg, acc, time_ms)) {106p.true_yaw = wrap_360_cd(yaw_deg*100);107} else {108p.true_yaw = 65535; // unknown109}110uint64_t tepoch_us = gps.time_epoch_usec(0);111time_t utc_sec = tepoch_us / (1000U * 1000U);112struct tm tvd {};113struct tm* tm = gmtime_r(&utc_sec, &tvd);114115p.year = tm->tm_year+1900;116p.month = tm->tm_mon;117p.day = tm->tm_mday;118p.hour = tm->tm_hour;119p.min = tm->tm_min;120p.sec = tm->tm_sec;121122send_msp_packet(MSP2_SENSOR_GPS, &p, sizeof(p));123}124#endif // HAL_PERIPH_ENABLE_GPS125126127#ifdef HAL_PERIPH_ENABLE_BARO128/*129send MSP baro packet130*/131void AP_Periph_FW::send_msp_baro(void)132{133MSP::msp_baro_data_message_t p;134135if (msp.last_baro_ms == baro.get_last_update(0)) {136return;137}138if (!baro.healthy()) {139// don't send any data140return;141}142msp.last_baro_ms = baro.get_last_update(0);143144p.instance = 0;145p.time_ms = msp.last_baro_ms;146p.pressure_pa = baro.get_pressure();147p.temp = baro.get_temperature() * 100;148149send_msp_packet(MSP2_SENSOR_BAROMETER, &p, sizeof(p));150}151#endif // HAL_PERIPH_ENABLE_BARO152153#ifdef HAL_PERIPH_ENABLE_MAG154/*155send MSP compass packet156*/157void AP_Periph_FW::send_msp_compass(void)158{159MSP::msp_compass_data_message_t p;160161if (msp.last_mag_ms == compass.last_update_ms(0)) {162return;163}164if (!compass.healthy()) {165return;166}167msp.last_mag_ms = compass.last_update_ms(0);168169const Vector3f &field = compass.get_field(0);170p.instance = 0;171p.time_ms = msp.last_mag_ms;172p.magX = field.x;173p.magY = field.y;174p.magZ = field.z;175176send_msp_packet(MSP2_SENSOR_COMPASS, &p, sizeof(p));177}178#endif // HAL_PERIPH_ENABLE_MAG179180#ifdef HAL_PERIPH_ENABLE_AIRSPEED181/*182send MSP airspeed packet183*/184void AP_Periph_FW::send_msp_airspeed(void)185{186MSP::msp_airspeed_data_message_t p;187188const uint32_t last_update_ms = airspeed.last_update_ms();189if (msp.last_airspeed_ms == last_update_ms) {190return;191}192if (!airspeed.healthy()) {193// we don't report at all for an unhealthy sensor. This maps194// to unhealthy in the flight controller driver195return;196}197msp.last_airspeed_ms = last_update_ms;198199p.instance = 0;200p.time_ms = msp.last_airspeed_ms;201p.pressure = airspeed.get_corrected_pressure();202float temp;203if (!airspeed.get_temperature(temp)) {204p.temp = INT16_MIN; //invalid temperature205} else {206p.temp = temp * 100;207}208209send_msp_packet(MSP2_SENSOR_AIRSPEED, &p, sizeof(p));210}211#endif // HAL_PERIPH_ENABLE_AIRSPEED212213214#endif // HAL_PERIPH_ENABLE_MSP215216217