#pragma once /* ./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:sagetech_mxs --no-configure --map param set SERIAL5_PROTOCOL 35 # ADSB param set ADSB_TYPE 4 # Sagetech MX Series param set SIM_ADSB_TYPES 8 # Sagetech MX Series param set SIM_ADSB_COUNT 5 param set SIM_ADSB_RADIUS 2000 # same as ADSB_LIST_RADIUS */ #include "SIM_config.h" #if AP_SIM_ADSB_SAGETECH_MXS_ENABLED #include "SIM_ADSB_Device.h" #include #include namespace SITL { class ADSB_Sagetech_MXS : public ADSB_Device { public: using ADSB_Device::ADSB_Device; void update(const class Aircraft *sitl_model); private: void update_serial_input(); void update_serial_output(const Aircraft *sitl_model); void update_serial_output_vehicles(const Aircraft *sitl_model); // pack a floating-point latitude or longitude into three bytes // according to Sagetech definitions: void pack_scaled_geocoord(uint8_t buf[3], float coord); void pack_scaled_alt(uint8_t buf[3], float alt_m); uint8_t scaled_groundspeed(float speed_m_s) const; void pack_scaled_groundspeed(uint8_t dest[1], float speed_m_s) const; void pack_scaled_airspeed(uint8_t dest[2], float speed_m_s) const; void pack_scaled_vertical_rate(uint8_t dest[2], float speed_m_s) const; // pack the three lower bytes of source into dest: void pack_int32_into_uint8_ts(int32_t source, uint8_t dest[3]); void send_vehicle_message(const class ADSB_Vehicle &vehicle); void send_vehicle_message_state_vector(const class ADSB_Vehicle &vehicle); void send_vehicle_message_status_report(const class ADSB_Vehicle &vehicle); void update_rf_output(); void update_rf_input(); enum class MsgType : uint8_t { INSTALLATION = 0x01, FLIGHTID = 0x02, OPMSG = 0x03, GPS = 0x04, DATAREQ = 0x05, TARGETREQUEST = 0x0B, ACK = 0x80, STATEVECTORREPORT = 0x91, MODESTATUSREPORT = 0x92, }; template class PACKED PackedMessage { public: PackedMessage(T _msg, MsgType _msgtype, uint8_t _msgid) : msg{_msg}, msgtype{_msgtype}, msgid{_msgid} { update_checksum(); } uint8_t preamble { 0xAA }; MsgType msgtype; uint8_t msgid; uint8_t payloadlen = sizeof(T); T msg; uint8_t checksum; uint16_t calculate_checksum(uint16_t len) const WARN_IF_UNUSED { uint8_t ret = 0; for (uint8_t i=0; i class PACKED StateVectorReportBuffer { public: uint8_t buffer[SIZE]; }; // 0x92 - ADSB Status Report. Note that this structure is // full-sized, assuming that the report structure field is indicating // all fields present. Actual parsing of this packet would // require looking at the report structure. class PACKED ModeStatusReport { public: uint32_t report_structure : 24; uint16_t validity_flags; uint8_t participant_address[3]; uint8_t address_qualifier; uint8_t report_times_of_applicability[6]; uint8_t callsign[8]; uint8_t emitter_category; uint8_t av_length_and_width_code; uint8_t emergency_priority_status; uint32_t capability_class_codes : 24; uint16_t operational_mode; uint8_t sv_quality_nacp; uint8_t sv_quality_nacv; uint8_t sv_quality_sil_and_sda; uint8_t sv_quality_gva; uint8_t sv_quality_nic; uint8_t sv_quality_track_heading_and_horizontal_reference_direction; uint8_t vertical_rate_type; uint8_t reserved[2]; }; template class PACKED ModeStatusReportBuffer { public: uint8_t buffer[SIZE]; }; union u { u() {} char buffer[280]; // from-autopilot PackedMessage packed_installation; PackedMessage packed_flightidmessage; PackedMessage packed_operating; PackedMessage packed_gps; PackedMessage packed_data_req; PackedMessage packed_target_req; PackedMessage packed_ack; // we probably don't get ACKs from the autopilot.... PackedMessage packed_state_vector_report; PackedMessage packed_status_report; struct PACKED { uint8_t start_byte; MsgType msgtype; uint8_t msgid; uint8_t payload_length; } preamble; } msg; uint8_t buflen; // called when there is a message in the buffer which should be // handled. If they return true then an ACK is sent. bool handle_message(const SITL::ADSB_Sagetech_MXS::Installation&); bool handle_message(const SITL::ADSB_Sagetech_MXS::FlightIDMessage&); bool handle_message(const SITL::ADSB_Sagetech_MXS::Operating&); bool handle_message(const SITL::ADSB_Sagetech_MXS::GPS&); bool handle_message(const SITL::ADSB_Sagetech_MXS::DataRequest&); bool handle_message(const SITL::ADSB_Sagetech_MXS::TargetRequest&); // bool handle_message(const SITL::ADSB_Sagetech_MXS::StateVectorReport&); bool _handle_message(); void handle_message(); double lon_string_to_double(const uint8_t *lat); double lat_string_to_double(const uint8_t *lng); /* * Simulated device state and methods */ struct { bool send; MsgType ackType; uint8_t ackId; } ack_info; uint8_t msgid; struct { struct { double lat; double lng; } gps; } info_from_vehicle; void assert_good_flight_id(); char flight_id[8]; uint32_t flight_id_set_time_ms; /* serial parsing methods and data */ // packet structure: // 1-byte start-byte // 1-byte msgtype // 1-byte msgid (sequence number) // 1-byte payloadlen // n-bytes payload // 1-byte checksum (sum of all previous bytes in packet % 256 void move_preamble_in_buffer(uint8_t search_start_pos=0); enum class InputState { WANT_START_BYTE = 56, WANT_PREAMBLE = 57, WANT_PAYLOAD = 60, WANT_CHECKSUM = 61, } input_state = InputState::WANT_START_BYTE; void set_input_state(InputState newstate) { // ::fprintf(stderr, "Moving from inputstate (%u) to (%u)\n", (uint8_t)_inputstate, (uint8_t)newstate); input_state = newstate; } }; } // namespace SITL #endif // AP_SIM_ADSB_SAGETECH_MXS_ENABLED