Skip to content

Commit

Permalink
FeasibilityChecker: Add new TakeoffLandAvailable option
Browse files Browse the repository at this point in the history
ADd a new misison feasiblity checker option to check if a proper landing approach is defined when in air. There must be at least a mission landing or a VTOL approach defined in order for the mission to be accepted. Else, use the same logic as in MIS_TKO_LAND_REQ=4
  • Loading branch information
KonradRudin committed Feb 15, 2024
1 parent bf2db62 commit 6090040
Show file tree
Hide file tree
Showing 3 changed files with 45 additions and 9 deletions.
46 changes: 37 additions & 9 deletions src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,12 @@ void FeasibilityChecker::updateData()
_current_position_lat_lon = matrix::Vector2d(vehicle_global_position.lat, vehicle_global_position.lon);
}

if (_rtl_status_sub.updated()) {
rtl_status_s rtl_status = {};
_rtl_status_sub.copy(&rtl_status);
_has_vtol_approach = rtl_status.has_vtol_approach;
}

param_t handle = param_find("FW_LND_ANG");

if (handle != PARAM_INVALID) {
Expand Down Expand Up @@ -577,17 +583,22 @@ bool FeasibilityChecker::checkTakeoffLandAvailable()
break;

case 4:
result = _has_takeoff == _landing_valid;
result = hasMissionBothOrNeitherTakeoffAndLanding();

break;

if (!result && (_has_takeoff)) {
mavlink_log_critical(_mavlink_log_pub, "Mission rejected: Add Landing item or remove Takeoff.\t");
events::send(events::ID("navigator_mis_add_land_or_rm_to"), {events::Log::Error, events::LogInternal::Info},
"Mission rejected: Add Landing item or remove Takeoff");
case 5:
if (!_is_landed && !_has_vtol_approach) {
result = _landing_valid;

} else if (!result && (_landing_valid)) {
mavlink_log_critical(_mavlink_log_pub, "Mission rejected: Add Takeoff item or remove Landing.\t");
events::send(events::ID("navigator_mis_add_to_or_rm_land"), {events::Log::Error, events::LogInternal::Info},
"Mission rejected: Add Takeoff item or remove Landing");
if (!result) {
mavlink_log_critical(_mavlink_log_pub, "Mission rejected: Landing waypoint/pattern required.");
events::send(events::ID("feasibility_mis_in_air_landing_req"), {events::Log::Error, events::LogInternal::Info},
"Mission rejected: Landing waypoint/pattern required");
}

} else {
result = hasMissionBothOrNeitherTakeoffAndLanding();
}

break;
Expand All @@ -600,6 +611,23 @@ bool FeasibilityChecker::checkTakeoffLandAvailable()
return result;
}

bool FeasibilityChecker::hasMissionBothOrNeitherTakeoffAndLanding()
{
bool result{_has_takeoff == _landing_valid};

if (!result && (_has_takeoff)) {
mavlink_log_critical(_mavlink_log_pub, "Mission rejected: Add Landing item or remove Takeoff.\t");
events::send(events::ID("navigator_mis_add_land_or_rm_to"), {events::Log::Error, events::LogInternal::Info},
"Mission rejected: Add Landing item or remove Takeoff");

} else if (!result && (_landing_valid)) {
mavlink_log_critical(_mavlink_log_pub, "Mission rejected: Add Takeoff item or remove Landing.\t");
events::send(events::ID("navigator_mis_add_to_or_rm_land"), {events::Log::Error, events::LogInternal::Info},
"Mission rejected: Add Takeoff item or remove Landing");
}

return result;
}

bool FeasibilityChecker::checkHorizontalDistanceToFirstWaypoint(mission_item_s &mission_item)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include "../navigation.h"
#include <mathlib/mathlib.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/rtl_status.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_land_detected.h>
Expand Down Expand Up @@ -97,6 +98,7 @@ class FeasibilityChecker : public ModuleParams
uORB::Subscription _status_sub{ORB_ID(vehicle_status)};
uORB::Subscription _land_detector_sub{ORB_ID(vehicle_land_detected)};
uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)};
uORB::Subscription _rtl_status_sub{ORB_ID(rtl_status)};

// parameters
float _param_fw_lnd_ang{0.f};
Expand All @@ -106,6 +108,7 @@ class FeasibilityChecker : public ModuleParams

bool _is_landed{false};
float _home_alt_msl{NAN};
bool _has_vtol_approach{false};
matrix::Vector2d _home_lat_lon = matrix::Vector2d((double)NAN, (double)NAN);
matrix::Vector2d _current_position_lat_lon = matrix::Vector2d((double)NAN, (double)NAN);
VehicleType _vehicle_type{VehicleType::RotaryWing};
Expand Down Expand Up @@ -247,4 +250,8 @@ class FeasibilityChecker : public ModuleParams
* @return False if the check failed.
*/
void doMulticopterChecks(mission_item_s &mission_item, const int current_index);

// Helper functions

bool hasMissionBothOrNeitherTakeoffAndLanding();
};
1 change: 1 addition & 0 deletions src/modules/navigator/mission_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 2.5f);
* @value 2 Require a landing
* @value 3 Require a takeoff and a landing
* @value 4 Require both a takeoff and a landing, or neither
* @value 5 Same as previous, but require a landing if in air and no valid VTOL landing approach is present
* @group Mission
*/
PARAM_DEFINE_INT32(MIS_TKO_LAND_REQ, 0);
Expand Down

0 comments on commit 6090040

Please sign in to comment.