1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980 |
- #pragma once
- #include <AP_HAL/utility/Socket.h>
- #include "SIM_Aircraft.h"
- namespace SITL {
- class ADSB_Vehicle {
- friend class ADSB;
- private:
- void update(float delta_t);
-
- Vector3f position;
- Vector3f velocity_ef;
- char callsign[9];
- uint32_t ICAO_address;
- bool initialised = false;
- };
-
- class ADSB {
- public:
- ADSB(const struct sitl_fdm &_fdm, const char *home_str);
- void update(void);
- private:
- const char *target_address = "127.0.0.1";
- const uint16_t target_port = 5762;
- Location home;
- uint8_t num_vehicles = 0;
- static const uint8_t num_vehicles_MAX = 200;
- ADSB_Vehicle vehicles[num_vehicles_MAX];
-
-
- const float reporting_period_ms = 1000;
- uint32_t last_report_us = 0;
- uint32_t last_update_us = 0;
- uint32_t last_tx_report_ms = 0;
-
- uint32_t last_heartbeat_ms = 0;
- bool seen_heartbeat = false;
- uint8_t vehicle_system_id;
- uint8_t vehicle_component_id;
- SocketAPM mav_socket { false };
- struct {
-
- bool connected;
- mavlink_message_t rxmsg;
- mavlink_status_t status;
- uint8_t seq;
- } mavlink {};
- void send_report(void);
- };
- }
|