44 ICAO_address = (uint32_t)(rand() % 10000);
45 snprintf(callsign,
sizeof(callsign),
"SIM%u", ICAO_address);
50 double vel_min = 5, vel_max = 20;
51 if (position.length() > 500) {
54 }
else if (position.length() > 10000) {
63 position += velocity_ef * delta_t;
75 if (_sitl ==
nullptr) {
127 while ((ret=
mav_socket.recv(buf,
sizeof(buf), 0)) > 0) {
128 for (uint8_t i=0; i<ret; i++) {
129 mavlink_message_t msg;
133 &msg, &status) == MAVLINK_FRAMING_OK) {
135 case MAVLINK_MSG_ID_HEARTBEAT: {
154 mavlink_message_t msg;
158 mavlink_heartbeat_t heartbeat;
159 heartbeat.type = MAV_TYPE_ADSB;
160 heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
161 heartbeat.base_mode = 0;
162 heartbeat.system_status = 0;
163 heartbeat.mavlink_version = 0;
164 heartbeat.custom_mode = 0;
170 mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
171 uint8_t saved_seq = chan0_status->current_tx_seq;
172 chan0_status->current_tx_seq =
mavlink.seq;
176 chan0_status->current_tx_seq = saved_seq;
200 mavlink_adsb_vehicle_t adsb_vehicle {};
204 adsb_vehicle.lat = loc.
lat;
205 adsb_vehicle.lon = loc.
lng;
206 adsb_vehicle.altitude_type = ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
207 adsb_vehicle.altitude = -vehicle.
position.
z * 1000;
210 adsb_vehicle.ver_velocity = -vehicle.
velocity_ef.
z * 100;
211 memcpy(adsb_vehicle.callsign, vehicle.
callsign,
sizeof(adsb_vehicle.callsign));
212 adsb_vehicle.emitter_type = ADSB_EMITTER_TYPE_LARGE;
213 adsb_vehicle.tslc = 1;
215 ADSB_FLAGS_VALID_COORDS |
216 ADSB_FLAGS_VALID_ALTITUDE |
217 ADSB_FLAGS_VALID_HEADING |
218 ADSB_FLAGS_VALID_VELOCITY |
219 ADSB_FLAGS_VALID_CALLSIGN |
220 ADSB_FLAGS_SIMULATED;
221 adsb_vehicle.squawk = 0;
223 mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
224 uint8_t saved_seq = chan0_status->current_tx_seq;
225 chan0_status->current_tx_seq =
mavlink.seq;
228 &msg, &adsb_vehicle);
229 chan0_status->current_tx_seq = saved_seq;
232 len = mavlink_msg_to_send_buffer(msgbuf, &msg);
243 mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
244 uint8_t saved_seq = chan0_status->current_tx_seq;
245 uint8_t saved_flags = chan0_status->flags;
246 chan0_status->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
247 chan0_status->current_tx_seq =
mavlink.seq;
248 const mavlink_uavionix_adsb_transceiver_health_report_t health_report = {UAVIONIX_ADSB_RF_HEALTH_OK};
249 len = mavlink_msg_uavionix_adsb_transceiver_health_report_encode(
vehicle_system_id,
251 &msg, &health_report);
252 chan0_status->current_tx_seq = saved_seq;
253 chan0_status->flags = saved_flags;
256 len = mavlink_msg_to_send_buffer(msgbuf, &msg);
259 ::printf(
"ADSBsim send tx health packet\n");
float norm(const T first, const U second, const Params... parameters)
int printf(const char *fmt,...)
static AP_Param * find_object(const char *name)
uint32_t last_tx_report_ms
AP_Int16 adsb_plane_count
const float reporting_period_ms
ADSB_Vehicle vehicles[num_vehicles_MAX]
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
const uint16_t target_port
struct SITL::ADSB::@198 mavlink
float get_distance(const struct Location &loc1, const struct Location &loc2)
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
int32_t lat
param 3 - Latitude * 10**7
static double rand_normal(double mean, double stddev)
static const uint8_t num_vehicles_MAX
uint32_t last_heartbeat_ms
static bool parse_home(const char *home_str, Location &loc, float &yaw_degrees)
const char * target_address
static DummyVehicle vehicle
int32_t lng
param 4 - Longitude * 10**7
int snprintf(char *str, size_t size, const char *fmt,...)
void update(float delta_t)
uint8_t vehicle_system_id
uint8_t vehicle_component_id
ADSB(const struct sitl_fdm &_fdm, const char *home_str)