Skip to content

Commit

Permalink
navigator: moved navigation modes initialize to class
Browse files Browse the repository at this point in the history
- save some memory by reduce the navigation mode array size
- iterate by using auto
  • Loading branch information
BazookaJoe1900 committed Oct 4, 2023
1 parent 7457097 commit 82a2679
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 30 deletions.
24 changes: 14 additions & 10 deletions src/modules/navigator/navigator.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,11 @@ using namespace time_literals;
/**
* Number of navigation modes that need on_active/on_inactive calls
*/
#define NAVIGATOR_MODE_ARRAY_SIZE 8
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
#define NAVIGATOR_MODE_ARRAY_SIZE 7
#else
#define NAVIGATOR_MODE_ARRAY_SIZE 6
#endif

class Navigator : public ModuleBase<Navigator>, public ModuleParams
{
Expand Down Expand Up @@ -331,24 +335,24 @@ class Navigator : public ModuleBase<Navigator>, public ModuleParams

perf_counter_t _loop_perf; /**< loop performance counter */

Geofence _geofence; /**< class that handles the geofence */
GeofenceBreachAvoidance _gf_breach_avoidance;
Geofence _geofence{this}; /**< class that handles the geofence */
GeofenceBreachAvoidance _gf_breach_avoidance{this};
hrt_abstime _last_geofence_check = 0;

bool _geofence_violation_warning_sent{false}; /**< prevents spaming to mavlink */
bool _pos_sp_triplet_updated{false}; /**< flags if position SP triplet needs to be published */
bool _pos_sp_triplet_published_invalid_once{false}; /**< flags if position SP triplet has been published once to UORB */
bool _mission_result_updated{false}; /**< flags if mission result has seen an update */

Mission _mission; /**< class that handles the missions */
Loiter _loiter; /**< class that handles loiter */
Takeoff _takeoff; /**< class for handling takeoff commands */
Mission _mission{this}; /**< class that handles the missions */
Loiter _loiter{this}; /**< class that handles loiter */
Takeoff _takeoff{this}; /**< class for handling takeoff commands */
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
VtolTakeoff _vtol_takeoff; /**< class for handling VEHICLE_CMD_NAV_VTOL_TAKEOFF command */
VtolTakeoff _vtol_takeoff {this}; /**< class for handling VEHICLE_CMD_NAV_VTOL_TAKEOFF command */
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
Land _land; /**< class for handling land commands */
PrecLand _precland; /**< class for handling precision land commands */
RTL _rtl; /**< class that handles RTL */
Land _land {this}; /**< class for handling land commands */
PrecLand _precland{this}; /**< class for handling precision land commands */
RTL _rtl{this}; /**< class that handles RTL */
AdsbConflict _adsb_conflict; /**< class that handles ADSB conflict avoidance */

NavigatorMode *_navigation_mode{nullptr}; /**< abstract pointer to current navigation mode class */
Expand Down
25 changes: 5 additions & 20 deletions src/modules/navigator/navigator_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,18 +69,7 @@ Navigator *g_navigator;

Navigator::Navigator() :
ModuleParams(nullptr),
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
_geofence(this),
_gf_breach_avoidance(this),
_mission(this),
_loiter(this),
_takeoff(this),
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
_vtol_takeoff(this),
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
_land(this),
_precland(this),
_rtl(this)
_loop_perf(perf_alloc(PC_ELAPSED, "navigator"))
{
/* Create a list of our possible navigation types */
_navigation_mode_array[0] = &_mission;
Expand All @@ -94,10 +83,8 @@ Navigator::Navigator() :
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF

/* iterate through navigation modes and initialize _mission_item for each */
for (unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) {
if (_navigation_mode_array[i]) {
_navigation_mode_array[i]->initialize();
}
for (auto &navigation_mode_array_item : _navigation_mode_array) {
navigation_mode_array_item->initialize();
}

_handle_back_trans_dec_mss = param_find("VT_B_DEC_MSS");
Expand Down Expand Up @@ -811,10 +798,8 @@ void Navigator::run()
_navigation_mode = navigation_mode_new;

/* iterate through navigation modes and set active/inactive for each */
for (unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) {
if (_navigation_mode_array[i]) {
_navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]);
}
for (auto &navigation_mode_array_item : _navigation_mode_array) {
navigation_mode_array_item->run(_navigation_mode == navigation_mode_array_item);
}

/* if nothing is running, set position setpoint triplet invalid once */
Expand Down

0 comments on commit 82a2679

Please sign in to comment.