2015-11-18 21:20:01 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
ADSB simulator class for MAVLink ADSB peripheral
|
|
|
|
*/
|
|
|
|
|
2023-05-12 02:53:31 -03:00
|
|
|
#include "SIM_config.h"
|
2021-10-11 01:59:19 -03:00
|
|
|
|
|
|
|
#if HAL_SIM_ADSB_ENABLED
|
|
|
|
|
2023-05-12 02:53:31 -03:00
|
|
|
#include "SIM_ADSB.h"
|
|
|
|
|
2016-06-15 00:47:19 -03:00
|
|
|
#include "SITL.h"
|
2015-11-18 21:20:01 -04:00
|
|
|
|
|
|
|
#include <stdio.h>
|
|
|
|
|
|
|
|
#include "SIM_Aircraft.h"
|
2019-08-15 03:53:35 -03:00
|
|
|
#include <AP_HAL_SITL/SITL_State.h>
|
2023-10-20 01:56:40 -03:00
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
2015-11-18 21:20:01 -04:00
|
|
|
|
|
|
|
namespace SITL {
|
|
|
|
|
|
|
|
/*
|
|
|
|
update a simulated vehicle
|
|
|
|
*/
|
2023-10-31 05:09:11 -03:00
|
|
|
void ADSB_Vehicle::update(const class Aircraft &aircraft, float delta_t)
|
2015-11-18 21:20:01 -04:00
|
|
|
{
|
2023-10-31 05:09:11 -03:00
|
|
|
const SIM *_sitl = AP::sitl();
|
|
|
|
if (_sitl == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
const Location &origin { aircraft.get_origin() };
|
2021-11-09 02:23:35 -04:00
|
|
|
|
2023-10-31 05:09:11 -03:00
|
|
|
if (!initialised) {
|
|
|
|
// spawn another aircraft
|
2015-11-18 21:20:01 -04:00
|
|
|
initialised = true;
|
|
|
|
ICAO_address = (uint32_t)(rand() % 10000);
|
|
|
|
snprintf(callsign, sizeof(callsign), "SIM%u", ICAO_address);
|
2023-10-31 05:09:11 -03:00
|
|
|
Location aircraft_location = aircraft.get_location();
|
|
|
|
const Vector2f aircraft_offset_ne = aircraft_location.get_distance_NE(origin);
|
|
|
|
position.x = aircraft_offset_ne[1];
|
|
|
|
position.y = aircraft_offset_ne[0];
|
|
|
|
position.x += Aircraft::rand_normal(0, _sitl->adsb_radius_m);
|
|
|
|
position.y += Aircraft::rand_normal(0, _sitl->adsb_radius_m);
|
2016-06-15 00:47:19 -03:00
|
|
|
position.z = -fabsf(_sitl->adsb_altitude_m);
|
|
|
|
|
|
|
|
double vel_min = 5, vel_max = 20;
|
|
|
|
if (position.length() > 500) {
|
|
|
|
vel_min *= 3;
|
|
|
|
vel_max *= 3;
|
|
|
|
} else if (position.length() > 10000) {
|
|
|
|
vel_min *= 10;
|
|
|
|
vel_max *= 10;
|
|
|
|
}
|
2019-11-18 16:17:51 -04:00
|
|
|
type = (ADSB_EMITTER_TYPE)(rand() % (ADSB_EMITTER_TYPE_POINT_OBSTACLE + 1));
|
|
|
|
// don't allow surface emitters to move
|
|
|
|
if (type == ADSB_EMITTER_TYPE_POINT_OBSTACLE) {
|
2021-11-18 18:25:11 -04:00
|
|
|
stationary_object_created_ms = AP_HAL::millis64();
|
2019-11-18 16:17:51 -04:00
|
|
|
velocity_ef.zero();
|
|
|
|
} else {
|
2021-11-18 18:25:11 -04:00
|
|
|
stationary_object_created_ms = 0;
|
2019-11-18 16:17:51 -04:00
|
|
|
velocity_ef.x = Aircraft::rand_normal(vel_min, vel_max);
|
|
|
|
velocity_ef.y = Aircraft::rand_normal(vel_min, vel_max);
|
|
|
|
if (type < ADSB_EMITTER_TYPE_EMERGENCY_SURFACE) {
|
|
|
|
velocity_ef.z = Aircraft::rand_normal(-3, 3);
|
|
|
|
}
|
|
|
|
}
|
2021-11-18 18:25:11 -04:00
|
|
|
} else if (stationary_object_created_ms > 0 && AP_HAL::millis64() - stationary_object_created_ms > AP_MSEC_PER_HOUR) {
|
|
|
|
// regenerate stationary objects so we don't randomly fill up the screen with them over time
|
|
|
|
initialised = false;
|
2015-11-18 21:20:01 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
position += velocity_ef * delta_t;
|
|
|
|
if (position.z > 0) {
|
|
|
|
// it has crashed! reset
|
|
|
|
initialised = false;
|
|
|
|
}
|
2023-10-31 05:09:11 -03:00
|
|
|
|
|
|
|
Location ret = origin;
|
|
|
|
ret.offset(position.x, position.y);
|
|
|
|
|
|
|
|
location = ret;
|
2015-11-18 21:20:01 -04:00
|
|
|
}
|
|
|
|
|
2023-10-31 05:09:11 -03:00
|
|
|
const Location &ADSB_Vehicle::get_location() const
|
2023-10-20 01:56:40 -03:00
|
|
|
{
|
2023-10-31 05:09:11 -03:00
|
|
|
return location;
|
2023-10-20 01:56:40 -03:00
|
|
|
}
|
|
|
|
|
2015-11-18 21:20:01 -04:00
|
|
|
/*
|
|
|
|
update the ADSB peripheral state
|
|
|
|
*/
|
2023-10-20 01:56:40 -03:00
|
|
|
void ADSB::update_simulated_vehicles(const class Aircraft &aircraft)
|
2015-11-18 21:20:01 -04:00
|
|
|
{
|
2016-06-15 00:47:19 -03:00
|
|
|
if (_sitl == nullptr) {
|
2018-06-11 14:41:13 -03:00
|
|
|
_sitl = AP::sitl();
|
2016-06-15 00:47:19 -03:00
|
|
|
return;
|
|
|
|
} else if (_sitl->adsb_plane_count <= 0) {
|
|
|
|
return;
|
|
|
|
} else if (_sitl->adsb_plane_count >= num_vehicles_MAX) {
|
|
|
|
_sitl->adsb_plane_count.set_and_save(0);
|
|
|
|
num_vehicles = 0;
|
|
|
|
return;
|
|
|
|
} else if (num_vehicles != _sitl->adsb_plane_count) {
|
|
|
|
num_vehicles = _sitl->adsb_plane_count;
|
|
|
|
for (uint8_t i=0; i<num_vehicles_MAX; i++) {
|
|
|
|
vehicles[i].initialised = false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-11-18 21:20:01 -04:00
|
|
|
// calculate delta time in seconds
|
|
|
|
uint32_t now_us = AP_HAL::micros();
|
|
|
|
|
|
|
|
float delta_t = (now_us - last_update_us) * 1.0e-6f;
|
|
|
|
last_update_us = now_us;
|
|
|
|
|
2023-10-31 05:09:11 -03:00
|
|
|
// prune any aircraft which get too far away from our simulated vehicle:
|
|
|
|
const Location &aircraft_loc = aircraft.get_location();
|
2023-10-20 01:56:40 -03:00
|
|
|
|
2015-11-18 21:20:01 -04:00
|
|
|
for (uint8_t i=0; i<num_vehicles; i++) {
|
2023-10-31 05:09:11 -03:00
|
|
|
auto &vehicle = vehicles[i];
|
|
|
|
vehicle.update(aircraft, delta_t);
|
2023-10-20 01:56:40 -03:00
|
|
|
|
|
|
|
// re-init when exceeding radius range
|
2023-10-31 05:09:11 -03:00
|
|
|
if (aircraft_loc.get_distance(vehicle.get_location()) > _sitl->adsb_radius_m) {
|
2023-10-20 01:56:40 -03:00
|
|
|
vehicle.initialised = false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void ADSB::update(const class Aircraft &aircraft)
|
|
|
|
{
|
|
|
|
update_simulated_vehicles(aircraft);
|
|
|
|
|
|
|
|
// see if we should do a report.
|
|
|
|
if ((_sitl->adsb_types & (1U << (uint8_t)SIM::ADSBType::Shortcut)) == 0) {
|
|
|
|
// some other simulated device is in use (e.g. MXS)
|
|
|
|
return;
|
2015-11-18 21:20:01 -04:00
|
|
|
}
|
2023-10-20 01:56:40 -03:00
|
|
|
|
|
|
|
// bakwards compatability; the parameters specify ADSB simulation,
|
|
|
|
// but we are not configured to use a simulated ADSB driver.
|
|
|
|
// Pretend to be a uAvionix mavlink device:
|
2021-11-09 02:23:35 -04:00
|
|
|
send_report(aircraft);
|
2015-11-18 21:20:01 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
send a report to the vehicle control code over MAVLink
|
|
|
|
*/
|
2021-11-09 02:23:35 -04:00
|
|
|
void ADSB::send_report(const class Aircraft &aircraft)
|
2015-11-18 21:20:01 -04:00
|
|
|
{
|
2016-03-17 21:18:19 -03:00
|
|
|
if (AP_HAL::millis() < 10000) {
|
|
|
|
// simulated aircraft don't appear until 10s after startup. This avoids a windows
|
2023-12-11 13:13:24 -04:00
|
|
|
// threading issue with non-blocking sockets and the initial wait on SERIAL0
|
2016-03-17 21:18:19 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-11-18 21:20:01 -04:00
|
|
|
|
|
|
|
// check for incoming MAVLink messages
|
|
|
|
uint8_t buf[100];
|
|
|
|
ssize_t ret;
|
|
|
|
|
2021-11-09 02:23:35 -04:00
|
|
|
while ((ret=read_from_autopilot((char*)buf, sizeof(buf))) > 0) {
|
2015-11-18 21:20:01 -04:00
|
|
|
for (uint8_t i=0; i<ret; i++) {
|
|
|
|
mavlink_message_t msg;
|
|
|
|
mavlink_status_t status;
|
|
|
|
if (mavlink_frame_char_buffer(&mavlink.rxmsg, &mavlink.status,
|
|
|
|
buf[i],
|
|
|
|
&msg, &status) == MAVLINK_FRAMING_OK) {
|
|
|
|
switch (msg.msgid) {
|
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT: {
|
|
|
|
if (!seen_heartbeat) {
|
|
|
|
seen_heartbeat = true;
|
|
|
|
vehicle_component_id = msg.compid;
|
|
|
|
vehicle_system_id = msg.sysid;
|
|
|
|
::printf("ADSB using srcSystem %u\n", (unsigned)vehicle_system_id);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!seen_heartbeat) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
mavlink_message_t msg;
|
|
|
|
uint16_t len;
|
|
|
|
|
|
|
|
if (now - last_heartbeat_ms >= 1000) {
|
|
|
|
mavlink_heartbeat_t heartbeat;
|
|
|
|
heartbeat.type = MAV_TYPE_ADSB;
|
|
|
|
heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
|
|
|
|
heartbeat.base_mode = 0;
|
|
|
|
heartbeat.system_status = 0;
|
|
|
|
heartbeat.mavlink_version = 0;
|
|
|
|
heartbeat.custom_mode = 0;
|
|
|
|
|
2023-09-29 01:09:21 -03:00
|
|
|
len = mavlink_msg_heartbeat_encode_status(vehicle_system_id,
|
|
|
|
vehicle_component_id,
|
|
|
|
&mavlink.status,
|
|
|
|
&msg, &heartbeat);
|
2015-11-18 21:20:01 -04:00
|
|
|
|
2021-11-09 02:23:35 -04:00
|
|
|
write_to_autopilot((char*)&msg.magic, len);
|
2015-11-18 21:20:01 -04:00
|
|
|
|
|
|
|
last_heartbeat_ms = now;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
send a ADSB_VEHICLE messages
|
|
|
|
*/
|
|
|
|
uint32_t now_us = AP_HAL::micros();
|
2016-06-15 00:50:32 -03:00
|
|
|
if (now_us - last_report_us >= reporting_period_ms*1000UL) {
|
2015-11-18 21:20:01 -04:00
|
|
|
for (uint8_t i=0; i<num_vehicles; i++) {
|
2023-10-20 01:56:40 -03:00
|
|
|
const ADSB_Vehicle &vehicle = vehicles[i];
|
|
|
|
if (!vehicle.initialised) {
|
|
|
|
continue;
|
|
|
|
}
|
2015-11-18 21:20:01 -04:00
|
|
|
|
2023-10-31 05:09:11 -03:00
|
|
|
const Location &loc { vehicle.get_location() };
|
2015-11-18 21:20:01 -04:00
|
|
|
|
|
|
|
mavlink_adsb_vehicle_t adsb_vehicle {};
|
|
|
|
last_report_us = now_us;
|
|
|
|
|
|
|
|
adsb_vehicle.ICAO_address = vehicle.ICAO_address;
|
2015-11-25 19:25:18 -04:00
|
|
|
adsb_vehicle.lat = loc.lat;
|
|
|
|
adsb_vehicle.lon = loc.lng;
|
2015-11-18 21:20:01 -04:00
|
|
|
adsb_vehicle.altitude_type = ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
|
2015-12-08 17:39:33 -04:00
|
|
|
adsb_vehicle.altitude = -vehicle.position.z * 1000;
|
2016-03-17 21:18:19 -03:00
|
|
|
adsb_vehicle.heading = wrap_360_cd(100*degrees(atan2f(vehicle.velocity_ef.y, vehicle.velocity_ef.x)));
|
2016-04-16 06:58:46 -03:00
|
|
|
adsb_vehicle.hor_velocity = norm(vehicle.velocity_ef.x, vehicle.velocity_ef.y) * 100;
|
2015-12-08 17:39:33 -04:00
|
|
|
adsb_vehicle.ver_velocity = -vehicle.velocity_ef.z * 100;
|
2015-11-18 21:20:01 -04:00
|
|
|
memcpy(adsb_vehicle.callsign, vehicle.callsign, sizeof(adsb_vehicle.callsign));
|
2019-11-18 16:17:51 -04:00
|
|
|
adsb_vehicle.emitter_type = vehicle.type;
|
2015-11-18 21:20:01 -04:00
|
|
|
adsb_vehicle.tslc = 1;
|
|
|
|
adsb_vehicle.flags =
|
|
|
|
ADSB_FLAGS_VALID_COORDS |
|
|
|
|
ADSB_FLAGS_VALID_ALTITUDE |
|
|
|
|
ADSB_FLAGS_VALID_HEADING |
|
|
|
|
ADSB_FLAGS_VALID_VELOCITY |
|
|
|
|
ADSB_FLAGS_VALID_CALLSIGN |
|
2020-08-21 13:22:37 -03:00
|
|
|
ADSB_FLAGS_VALID_SQUAWK |
|
|
|
|
ADSB_FLAGS_SIMULATED |
|
|
|
|
ADSB_FLAGS_VERTICAL_VELOCITY_VALID |
|
|
|
|
ADSB_FLAGS_BARO_VALID;
|
|
|
|
// all flags set except ADSB_FLAGS_SOURCE_UAT
|
|
|
|
|
|
|
|
adsb_vehicle.squawk = 1200;
|
2015-11-18 21:20:01 -04:00
|
|
|
|
2023-09-29 01:09:21 -03:00
|
|
|
len = mavlink_msg_adsb_vehicle_encode_status(vehicle_system_id,
|
2015-11-18 21:20:01 -04:00
|
|
|
MAV_COMP_ID_ADSB,
|
2023-09-29 01:09:21 -03:00
|
|
|
&mavlink.status,
|
2015-11-18 21:20:01 -04:00
|
|
|
&msg, &adsb_vehicle);
|
2023-09-29 01:09:21 -03:00
|
|
|
|
2016-06-15 21:15:07 -03:00
|
|
|
uint8_t msgbuf[len];
|
|
|
|
len = mavlink_msg_to_send_buffer(msgbuf, &msg);
|
|
|
|
if (len > 0) {
|
2021-11-09 02:23:35 -04:00
|
|
|
write_to_autopilot((char*)msgbuf, len);
|
2016-06-15 21:15:07 -03:00
|
|
|
}
|
2015-11-18 21:20:01 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-08-16 18:16:03 -03:00
|
|
|
// ADSB_transceiever is enabled, send the status report.
|
|
|
|
if (_sitl->adsb_tx && now - last_tx_report_ms > 1000) {
|
|
|
|
last_tx_report_ms = now;
|
|
|
|
|
|
|
|
const mavlink_uavionix_adsb_transceiver_health_report_t health_report = {UAVIONIX_ADSB_RF_HEALTH_OK};
|
2023-09-29 01:09:21 -03:00
|
|
|
len = mavlink_msg_uavionix_adsb_transceiver_health_report_encode_status(vehicle_system_id,
|
|
|
|
MAV_COMP_ID_ADSB,
|
|
|
|
&mavlink.status,
|
|
|
|
&msg, &health_report);
|
2016-08-16 18:16:03 -03:00
|
|
|
|
|
|
|
uint8_t msgbuf[len];
|
|
|
|
len = mavlink_msg_to_send_buffer(msgbuf, &msg);
|
|
|
|
if (len > 0) {
|
2021-11-09 02:23:35 -04:00
|
|
|
write_to_autopilot((char*)msgbuf, len);
|
2016-08-16 19:29:35 -03:00
|
|
|
::printf("ADSBsim send tx health packet\n");
|
2016-08-16 18:16:03 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-11-18 21:20:01 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
} // namespace SITL
|
2021-10-11 01:59:19 -03:00
|
|
|
|
|
|
|
#endif // HAL_SIM_ADSB_ENABLED
|