mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
SITL: Add instance to ADSB simulation
This commit is contained in:
parent
85dbb70df5
commit
016edd28fc
@ -117,8 +117,8 @@ void ADSB::send_report(void)
|
||||
// threading issue with non-blocking sockets and the initial wait on uartA
|
||||
return;
|
||||
}
|
||||
if (!mavlink.connected && mav_socket.connect(target_address, target_port)) {
|
||||
::printf("ADSB connected to %s:%u\n", target_address, (unsigned)target_port);
|
||||
if (!mavlink.connected && mav_socket.connect(target_address, target_port_base + 10 * instance)) {
|
||||
::printf("ADSB connected to %s:%u\n", target_address, (unsigned)target_port_base + 10 * instance);
|
||||
mavlink.connected = true;
|
||||
}
|
||||
if (!mavlink.connected) {
|
||||
|
@ -51,12 +51,14 @@ private:
|
||||
|
||||
class ADSB {
|
||||
public:
|
||||
ADSB(const struct sitl_fdm &_fdm, const Location& _home) : home(_home) {};
|
||||
ADSB(const struct sitl_fdm &_fdm, const Location& _home, const uint8_t _instance) : home(_home), instance(_instance) {};
|
||||
void update(void);
|
||||
|
||||
private:
|
||||
const char *target_address = "127.0.0.1";
|
||||
const uint16_t target_port = 5762;
|
||||
const uint16_t target_port_base = 5762;
|
||||
|
||||
const uint8_t instance = 0;
|
||||
|
||||
const Location& home;
|
||||
uint8_t num_vehicles = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user