Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Treat UAVS diffrently from manned aviation #13159

Merged
merged 22 commits into from
Jan 17, 2020
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
0627f5d
ready 4 test
LowOrbitIonCannon Oct 11, 2019
792e182
Parameters and changes
LowOrbitIonCannon Nov 8, 2019
a37b245
Parameter for Unmanned and Manned Aviation Avoid Distance
LowOrbitIonCannon Nov 11, 2019
d80c566
Parameters Updated
LowOrbitIonCannon Nov 11, 2019
46683ed
Referenc ADSB_EMITER_TYPE Variable,
LowOrbitIonCannon Nov 12, 2019
eec96b5
Fixed Compiler Error by -Wno-cast-align
LowOrbitIonCannon Nov 13, 2019
2d6e930
Added Testing functionality,
LowOrbitIonCannon Nov 20, 2019
2df30d3
Added NAV_TRAFF_AVOID Hold and Landmode
LowOrbitIonCannon Nov 21, 2019
e52acc5
Added ADSB parameter to Transponder_report
LowOrbitIonCannon Nov 25, 2019
2bb5cd3
Fixed aligment issue from float to double by converting to INT.
LowOrbitIonCannon Nov 26, 2019
9191348
added Seperation as a value to Warning
LowOrbitIonCannon Nov 26, 2019
a3e580b
added Land Mode
LowOrbitIonCannon Nov 29, 2019
717d2fd
testing Traffic avoidance, distance and modes
LowOrbitIonCannon Nov 29, 2019
9632efb
Changed Warning messages and Merged HoldPosition and Collision Avoidance
LowOrbitIonCannon Dec 2, 2019
3c8e440
Merge branch 'testing' into r4t
LowOrbitIonCannon Dec 2, 2019
2d7ecfd
ignore selfsend UTM msg.
LowOrbitIonCannon Dec 9, 2019
4d5460d
Changed mavlink reciever to ignore selfüublished messages
LowOrbitIonCannon Dec 10, 2019
8afe944
Fixed boards with no GUID giving build Errors
LowOrbitIonCannon Dec 11, 2019
b9d1137
Reduced size to fit into px4-fmu-v2
LowOrbitIonCannon Dec 11, 2019
71d4a81
Merge branch 'master' into r4t
LowOrbitIonCannon Dec 11, 2019
c217c6a
Merge branch 'master' into r4t
LowOrbitIonCannon Jan 9, 2020
cbce64e
Merge branch 'master' into r4t
dagar Jan 17, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2229,7 +2229,7 @@ MavlinkReceiver::handle_message_utm_global_position(mavlink_message_t *msg)
// For now, set it to all 0s. This is a null-terminated string, so not explicitly giving it a null
// terminator could cause problems.
memset(&t.callsign[0], 0, sizeof(t.callsign));
t.emitter_type = ADSB_EMITTER_TYPE_NO_INFO; // TODO: Is this correct?
t.emitter_type = ADSB_EMITTER_TYPE_UAV; // TODO: Is this correct?x2?

// The Mavlink docs do not specify what to do if tslc (time since last communication) is out of range of
// an 8-bit int, or if this is the first communication.
Expand Down
1 change: 1 addition & 0 deletions src/modules/navigator/navigator.h
Original file line number Diff line number Diff line change
Expand Up @@ -301,6 +301,7 @@ class Navigator : public ModuleBase<Navigator>, public ModuleParams
_param_nav_mc_alt_rad, /**< acceptance radius for multicopter altitude */
(ParamInt<px4::params::NAV_FORCE_VT>) _param_nav_force_vt, /**< acceptance radius for multicopter altitude */
(ParamInt<px4::params::NAV_TRAFF_AVOID>) _param_nav_traff_avoid, /**< avoiding other aircraft is enabled */
(ParamInt<px4::params::NAV_TRAFF_A_RAD>) _param_nav_traff_a_rad, /**< avoidance Distance*/

// non-navigator parameters
// Mission (MIS_*)
Expand Down
7 changes: 7 additions & 0 deletions src/modules/navigator/navigator_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -960,6 +960,13 @@ void Navigator::check_traffic()
continue;
}


//ADSB Transmitter 14 = UAV
if (tr.emitter_type == ADSB_EMITTER_TYPE_UAV) {
horizontal_separation = _param_nav_traff_a_rad.get();
vertical_separation = _param_nav_traff_a_rad.get();
}

float d_hor, d_vert;
get_distance_to_point_global_wgs84(lat, lon, alt,
tr.lat, tr.lon, tr.altitude, &d_hor, &d_vert);
Expand Down