Skip to content

Commit

Permalink
Fix style. Move flags definitions to uORB message
Browse files Browse the repository at this point in the history
  • Loading branch information
svpcom committed Feb 18, 2018
1 parent 8550589 commit dcc80e5
Show file tree
Hide file tree
Showing 5 changed files with 47 additions and 35 deletions.
9 changes: 9 additions & 0 deletions msg/transponder_report.msg
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,13 @@ uint8 tslc # Time since last communication in seconds
uint16 flags # Flags to indicate various statuses including valid data fields
uint16 squawk # Squawk code

# ADSB flags
uint16 PX4_ADSB_FLAGS_VALID_COORDS = 1
uint16 PX4_ADSB_FLAGS_VALID_ALTITUDE = 2
uint16 PX4_ADSB_FLAGS_VALID_HEADING = 4
uint16 PX4_ADSB_FLAGS_VALID_VELOCITY = 8
uint16 PX4_ADSB_FLAGS_VALID_CALLSIGN = 16
uint16 PX4_ADSB_FLAGS_VALID_SQUAWK = 32
uint16 PX4_ADSB_FLAGS_RETRANSLATE = 256

uint32 ORB_QUEUE_LENGTH = 10
22 changes: 14 additions & 8 deletions src/modules/mavlink/mavlink_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@
#include <px4_time.h>
#include <systemlib/err.h>
#include <systemlib/mavlink_log.h>
#include <navigator/navigator.h>

#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/actuator_controls.h>
Expand Down Expand Up @@ -1346,7 +1345,8 @@ class MavlinkStreamADSBVehicle : public MavlinkStream

while (_pos_sub->update(&_pos_time, &pos)) {
mavlink_adsb_vehicle_t msg = {};
if (!(pos.flags & PX4_ADSB_FLAGS_RETRANSLATE)) { continue; }

if (!(pos.flags & transponder_report_s::PX4_ADSB_FLAGS_RETRANSLATE)) { continue; }

msg.ICAO_address = pos.ICAO_address;
msg.lat = pos.lat * 1e7;
Expand All @@ -1362,12 +1362,18 @@ class MavlinkStreamADSBVehicle : public MavlinkStream
msg.squawk = pos.squawk;

msg.flags = 0;
if (pos.flags & PX4_ADSB_FLAGS_VALID_COORDS) { msg.flags |= ADSB_FLAGS_VALID_COORDS; }
if (pos.flags & PX4_ADSB_FLAGS_VALID_ALTITUDE) { msg.flags |= ADSB_FLAGS_VALID_ALTITUDE; }
if (pos.flags & PX4_ADSB_FLAGS_VALID_HEADING) { msg.flags |= ADSB_FLAGS_VALID_HEADING; }
if (pos.flags & PX4_ADSB_FLAGS_VALID_VELOCITY) { msg.flags |= ADSB_FLAGS_VALID_VELOCITY; }
if (pos.flags & PX4_ADSB_FLAGS_VALID_CALLSIGN) { msg.flags |= ADSB_FLAGS_VALID_CALLSIGN; }
if (pos.flags & PX4_ADSB_FLAGS_VALID_SQUAWK) { msg.flags |= ADSB_FLAGS_VALID_SQUAWK; }

if (pos.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS) { msg.flags |= ADSB_FLAGS_VALID_COORDS; }

if (pos.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE) { msg.flags |= ADSB_FLAGS_VALID_ALTITUDE; }

if (pos.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING) { msg.flags |= ADSB_FLAGS_VALID_HEADING; }

if (pos.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY) { msg.flags |= ADSB_FLAGS_VALID_VELOCITY; }

if (pos.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN) { msg.flags |= ADSB_FLAGS_VALID_CALLSIGN; }

if (pos.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_SQUAWK) { msg.flags |= ADSB_FLAGS_VALID_SQUAWK; }

mavlink_msg_adsb_vehicle_send_struct(_mavlink->get_channel(), &msg);
sent = true;
Expand Down
21 changes: 13 additions & 8 deletions src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,6 @@
#include <systemlib/airspeed.h>
#include <commander/px4_custom_mode.h>
#include <geo/geo.h>
#include <navigator/navigator.h>

#include <uORB/topics/vehicle_command_ack.h>

Expand Down Expand Up @@ -2082,13 +2081,19 @@ void MavlinkReceiver::handle_message_adsb_vehicle(mavlink_message_t *msg)
t.tslc = adsb.tslc;
t.squawk = adsb.squawk;

t.flags = PX4_ADSB_FLAGS_RETRANSLATE; //Unset in receiver already broadcast its messages
if (adsb.flags & ADSB_FLAGS_VALID_COORDS) { t.flags |= PX4_ADSB_FLAGS_VALID_COORDS; }
if (adsb.flags & ADSB_FLAGS_VALID_ALTITUDE) { t.flags |= PX4_ADSB_FLAGS_VALID_ALTITUDE; }
if (adsb.flags & ADSB_FLAGS_VALID_HEADING) { t.flags |= PX4_ADSB_FLAGS_VALID_HEADING; }
if (adsb.flags & ADSB_FLAGS_VALID_VELOCITY) { t.flags |= PX4_ADSB_FLAGS_VALID_VELOCITY; }
if (adsb.flags & ADSB_FLAGS_VALID_CALLSIGN) { t.flags |= PX4_ADSB_FLAGS_VALID_CALLSIGN; }
if (adsb.flags & ADSB_FLAGS_VALID_SQUAWK) { t.flags |= PX4_ADSB_FLAGS_VALID_SQUAWK; }
t.flags = transponder_report_s::PX4_ADSB_FLAGS_RETRANSLATE; //Unset in receiver already broadcast its messages

if (adsb.flags & ADSB_FLAGS_VALID_COORDS) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS; }

if (adsb.flags & ADSB_FLAGS_VALID_ALTITUDE) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE; }

if (adsb.flags & ADSB_FLAGS_VALID_HEADING) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING; }

if (adsb.flags & ADSB_FLAGS_VALID_VELOCITY) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY; }

if (adsb.flags & ADSB_FLAGS_VALID_CALLSIGN) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN; }

if (adsb.flags & ADSB_FLAGS_VALID_SQUAWK) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_SQUAWK; }

//PX4_INFO("code: %d callsign: %s, vel: %8.4f, tslc: %d", (int)t.ICAO_address, t.callsign, (double)t.hor_velocity, (int)t.tslc);

Expand Down
11 changes: 0 additions & 11 deletions src/modules/navigator/navigator.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,17 +79,6 @@
*/
#define NAVIGATOR_MODE_ARRAY_SIZE 11

typedef enum adsb_transponder_flags_e
{
PX4_ADSB_FLAGS_VALID_COORDS=1, /* | */
PX4_ADSB_FLAGS_VALID_ALTITUDE=2, /* | */
PX4_ADSB_FLAGS_VALID_HEADING=4, /* | */
PX4_ADSB_FLAGS_VALID_VELOCITY=8, /* | */
PX4_ADSB_FLAGS_VALID_CALLSIGN=16, /* | */
PX4_ADSB_FLAGS_VALID_SQUAWK=32, /* | */
PX4_ADSB_FLAGS_RETRANSLATE=256, /* | */
} adsb_transponder_flags_t;


class Navigator : public control::SuperBlock
{
Expand Down
19 changes: 11 additions & 8 deletions src/modules/navigator/navigator_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -963,9 +963,10 @@ void Navigator::fake_traffic(const char *callsign, float distance, float directi
strncpy(&tr.callsign[0], callsign, sizeof(tr.callsign));
tr.emitter_type = 0; // Type from ADSB_EMITTER_TYPE enum
tr.tslc = 2; // Time since last communication in seconds
tr.flags = PX4_ADSB_FLAGS_VALID_COORDS | PX4_ADSB_FLAGS_VALID_HEADING | PX4_ADSB_FLAGS_VALID_VELOCITY | \
PX4_ADSB_FLAGS_VALID_ALTITUDE |
PX4_ADSB_FLAGS_VALID_CALLSIGN; // Flags to indicate various statuses including valid data fields
tr.flags = transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS | transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING |
transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY |
transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE |
transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN; // Flags to indicate various statuses including valid data fields
tr.squawk = 6667;

orb_advert_t h = orb_advertise_queue(ORB_ID(transponder_report), &tr, transponder_report_s::ORB_QUEUE_LENGTH);
Expand Down Expand Up @@ -995,8 +996,9 @@ void Navigator::check_traffic()
transponder_report_s tr;
orb_copy(ORB_ID(transponder_report), _traffic_sub, &tr);

uint16_t required_flags = PX4_ADSB_FLAGS_VALID_COORDS | PX4_ADSB_FLAGS_VALID_HEADING |
PX4_ADSB_FLAGS_VALID_VELOCITY | PX4_ADSB_FLAGS_VALID_ALTITUDE;
uint16_t required_flags = transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS |
transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING |
transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY | transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE;

if ((tr.flags & required_flags) != required_flags) {
orb_check(_traffic_sub, &changed);
Expand Down Expand Up @@ -1042,21 +1044,22 @@ void Navigator::check_traffic()

case 0: {
/* ignore */
PX4_WARN("TRAFFIC %s, hdg: %d", tr.flags & PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : "unknown",
PX4_WARN("TRAFFIC %s, hdg: %d", tr.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign :
"unknown",
traffic_direction);
break;
}

case 1: {
mavlink_log_critical(&_mavlink_log_pub, "WARNING TRAFFIC %s at heading %d, land immediately",
tr.flags & PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : "unknown",
tr.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : "unknown",
traffic_direction);
break;
}

case 2: {
mavlink_log_critical(&_mavlink_log_pub, "AVOIDING TRAFFIC %s heading %d, returning home",
tr.flags & PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : "unknown",
tr.flags & transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN ? tr.callsign : "unknown",
traffic_direction);

// set the return altitude to minimum
Expand Down

0 comments on commit dcc80e5

Please sign in to comment.