diff --git a/src/modules/navigator/datalinkloss.cpp b/src/modules/navigator/datalinkloss.cpp index 4374593966..bd11fd70bd 100644 --- a/src/modules/navigator/datalinkloss.cpp +++ b/src/modules/navigator/datalinkloss.cpp @@ -54,18 +54,9 @@ #include "navigator.h" #include "datalinkloss.h" -DataLinkLoss::DataLinkLoss(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), - _param_commsholdwaittime(this, "CH_T"), - _param_commsholdlat(this, "CH_LAT"), - _param_commsholdlon(this, "CH_LON"), - _param_commsholdalt(this, "CH_ALT"), - _param_airfieldhomelat(this, "NAV_AH_LAT", false), - _param_airfieldhomelon(this, "NAV_AH_LON", false), - _param_airfieldhomealt(this, "NAV_AH_ALT", false), - _param_airfieldhomewaittime(this, "AH_T"), - _param_numberdatalinklosses(this, "N"), - _param_skipcommshold(this, "CHSK"), +DataLinkLoss::DataLinkLoss(Navigator *navigator) : + MissionBlock(navigator), + ModuleParams(navigator), _dll_state(DLL_STATE_NONE) { } diff --git a/src/modules/navigator/datalinkloss.h b/src/modules/navigator/datalinkloss.h index ef52cfc860..e622b5c412 100644 --- a/src/modules/navigator/datalinkloss.h +++ b/src/modules/navigator/datalinkloss.h @@ -40,15 +40,17 @@ #ifndef NAVIGATOR_DATALINKLOSS_H #define NAVIGATOR_DATALINKLOSS_H +#include + #include "navigator_mode.h" #include "mission_block.h" class Navigator; -class DataLinkLoss final : public MissionBlock +class DataLinkLoss : public MissionBlock, public ModuleParams { public: - DataLinkLoss(Navigator *navigator, const char *name); + DataLinkLoss(Navigator *navigator); ~DataLinkLoss() = default; @@ -57,17 +59,18 @@ public: void on_active() override; private: - /* Params */ - control::BlockParamFloat _param_commsholdwaittime; - control::BlockParamInt _param_commsholdlat; // * 1e7 - control::BlockParamInt _param_commsholdlon; // * 1e7 - control::BlockParamFloat _param_commsholdalt; - control::BlockParamInt _param_airfieldhomelat; // * 1e7 - control::BlockParamInt _param_airfieldhomelon; // * 1e7 - control::BlockParamFloat _param_airfieldhomealt; - control::BlockParamFloat _param_airfieldhomewaittime; - control::BlockParamInt _param_numberdatalinklosses; - control::BlockParamInt _param_skipcommshold; + DEFINE_PARAMETERS( + (ParamFloat) _param_commsholdwaittime, + (ParamInt) _param_commsholdlat, // * 1e7 + (ParamInt) _param_commsholdlon, // * 1e7 + (ParamFloat) _param_commsholdalt, + (ParamInt) _param_airfieldhomelat, // * 1e7 + (ParamInt) _param_airfieldhomelon, // * 1e7 + (ParamFloat) _param_airfieldhomealt, + (ParamFloat) _param_airfieldhomewaittime, + (ParamInt) _param_numberdatalinklosses, + (ParamInt) _param_skipcommshold + ) enum DLLState { DLL_STATE_NONE = 0, diff --git a/src/modules/navigator/enginefailure.cpp b/src/modules/navigator/enginefailure.cpp index 77349d7f38..90c1897f9e 100644 --- a/src/modules/navigator/enginefailure.cpp +++ b/src/modules/navigator/enginefailure.cpp @@ -52,8 +52,8 @@ #include "navigator.h" #include "enginefailure.h" -EngineFailure::EngineFailure(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), +EngineFailure::EngineFailure(Navigator *navigator) : + MissionBlock(navigator), _ef_state(EF_STATE_NONE) { } diff --git a/src/modules/navigator/enginefailure.h b/src/modules/navigator/enginefailure.h index 2a5c0941f8..2b8f184b22 100644 --- a/src/modules/navigator/enginefailure.h +++ b/src/modules/navigator/enginefailure.h @@ -45,10 +45,10 @@ class Navigator; -class EngineFailure final : public MissionBlock +class EngineFailure : public MissionBlock { public: - EngineFailure(Navigator *navigator, const char *name); + EngineFailure(Navigator *navigator); ~EngineFailure() = default; void on_inactive() override; diff --git a/src/modules/navigator/follow_target.cpp b/src/modules/navigator/follow_target.cpp index 8bae416912..12af5ce22d 100644 --- a/src/modules/navigator/follow_target.cpp +++ b/src/modules/navigator/follow_target.cpp @@ -58,12 +58,9 @@ constexpr float FollowTarget::_follow_position_matricies[4][9]; -FollowTarget::FollowTarget(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), - _param_min_alt(this, "NAV_MIN_FT_HT", false), - _param_tracking_dist(this, "NAV_FT_DST", false), - _param_tracking_side(this, "NAV_FT_FS", false), - _param_tracking_resp(this, "NAV_FT_RS", false) +FollowTarget::FollowTarget(Navigator *navigator) : + MissionBlock(navigator), + ModuleParams(navigator) { _current_vel.zero(); _step_vel.zero(); diff --git a/src/modules/navigator/follow_target.h b/src/modules/navigator/follow_target.h index 853c73eeb7..742f391246 100644 --- a/src/modules/navigator/follow_target.h +++ b/src/modules/navigator/follow_target.h @@ -45,13 +45,14 @@ #include "navigator_mode.h" #include "mission_block.h" +#include #include -class FollowTarget final : public MissionBlock +class FollowTarget : public MissionBlock, public ModuleParams { public: - FollowTarget(Navigator *navigator, const char *name); + FollowTarget(Navigator *navigator); ~FollowTarget() = default; void on_inactive() override; @@ -107,10 +108,12 @@ private: }; // follow left side - control::BlockParamFloat _param_min_alt; - control::BlockParamFloat _param_tracking_dist; - control::BlockParamInt _param_tracking_side; - control::BlockParamFloat _param_tracking_resp; + DEFINE_PARAMETERS( + (ParamFloat) _param_min_alt, + (ParamFloat) _param_tracking_dist, + (ParamInt) _param_tracking_side, + (ParamFloat) _param_tracking_resp + ) FollowTargetState _follow_target_state{SET_WAIT_FOR_TARGET_POSITION}; int _follow_target_position{FOLLOW_FROM_BEHIND}; diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index bdff40a1e2..1171de9c40 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -53,14 +53,8 @@ #define GEOFENCE_RANGE_WARNING_LIMIT 5000000 Geofence::Geofence(Navigator *navigator) : - SuperBlock(navigator, "GF"), - _navigator(navigator), - _param_action(this, "GF_ACTION", false), - _param_altitude_mode(this, "GF_ALTMODE", false), - _param_source(this, "GF_SOURCE", false), - _param_counter_threshold(this, "GF_COUNT", false), - _param_max_hor_distance(this, "GF_MAX_HOR_DIST", false), - _param_max_ver_distance(this, "GF_MAX_VER_DIST", false) + ModuleParams(navigator), + _navigator(navigator) { // we assume there's no concurrent fence update on startup _updateFence(); diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h index 5fe4244a69..0314d44440 100644 --- a/src/modules/navigator/geofence.h +++ b/src/modules/navigator/geofence.h @@ -43,9 +43,7 @@ #include -#include -#include -#include +#include #include #include #include @@ -57,7 +55,7 @@ class Navigator; -class Geofence : public control::SuperBlock +class Geofence : public ModuleParams { public: Geofence(Navigator *navigator); @@ -159,13 +157,14 @@ private: map_projection_reference_s _projection_reference = {}; ///< reference to convert (lon, lat) to local [m] - /* Params */ - control::BlockParamInt _param_action; - control::BlockParamInt _param_altitude_mode; - control::BlockParamInt _param_source; - control::BlockParamInt _param_counter_threshold; - control::BlockParamFloat _param_max_hor_distance; - control::BlockParamFloat _param_max_ver_distance; + DEFINE_PARAMETERS( + (ParamInt) _param_action, + (ParamInt) _param_altitude_mode, + (ParamInt) _param_source, + (ParamInt) _param_counter_threshold, + (ParamFloat) _param_max_hor_distance, + (ParamFloat) _param_max_ver_distance + ) int _outside_counter{0}; uint16_t _update_counter{0}; ///< dataman update counter: if it does not match, we polygon data was updated diff --git a/src/modules/navigator/gpsfailure.cpp b/src/modules/navigator/gpsfailure.cpp index b554b91ef3..cd7d7d1704 100644 --- a/src/modules/navigator/gpsfailure.cpp +++ b/src/modules/navigator/gpsfailure.cpp @@ -51,12 +51,9 @@ using matrix::Eulerf; using matrix::Quatf; -GpsFailure::GpsFailure(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), - _param_loitertime(this, "LT"), - _param_openlooploiter_roll(this, "R"), - _param_openlooploiter_pitch(this, "P"), - _param_openlooploiter_thrust(this, "TR") +GpsFailure::GpsFailure(Navigator *navigator) : + MissionBlock(navigator), + ModuleParams(navigator) { } diff --git a/src/modules/navigator/gpsfailure.h b/src/modules/navigator/gpsfailure.h index ddf2ce2384..35227188f8 100644 --- a/src/modules/navigator/gpsfailure.h +++ b/src/modules/navigator/gpsfailure.h @@ -40,14 +40,16 @@ #ifndef NAVIGATOR_GPSFAILURE_H #define NAVIGATOR_GPSFAILURE_H +#include + #include "mission_block.h" class Navigator; -class GpsFailure final : public MissionBlock +class GpsFailure : public MissionBlock, public ModuleParams { public: - GpsFailure(Navigator *navigator, const char *name); + GpsFailure(Navigator *navigator); ~GpsFailure() = default; void on_inactive() override; @@ -55,11 +57,12 @@ public: void on_active() override; private: - /* Params */ - control::BlockParamFloat _param_loitertime; - control::BlockParamFloat _param_openlooploiter_roll; - control::BlockParamFloat _param_openlooploiter_pitch; - control::BlockParamFloat _param_openlooploiter_thrust; + DEFINE_PARAMETERS( + (ParamFloat) _param_loitertime, + (ParamFloat) _param_openlooploiter_roll, + (ParamFloat) _param_openlooploiter_pitch, + (ParamFloat) _param_openlooploiter_thrust + ) enum GPSFState { GPSF_STATE_NONE = 0, diff --git a/src/modules/navigator/land.cpp b/src/modules/navigator/land.cpp index 76bf62c873..fa72d541f2 100644 --- a/src/modules/navigator/land.cpp +++ b/src/modules/navigator/land.cpp @@ -41,8 +41,8 @@ #include "land.h" #include "navigator.h" -Land::Land(Navigator *navigator, const char *name) : - MissionBlock(navigator, name) +Land::Land(Navigator *navigator) : + MissionBlock(navigator) { } diff --git a/src/modules/navigator/land.h b/src/modules/navigator/land.h index 06ddca813b..01ae962ebb 100644 --- a/src/modules/navigator/land.h +++ b/src/modules/navigator/land.h @@ -47,7 +47,7 @@ class Land final : public MissionBlock { public: - Land(Navigator *navigator, const char *name); + Land(Navigator *navigator); ~Land() = default; void on_activation() override; diff --git a/src/modules/navigator/loiter.cpp b/src/modules/navigator/loiter.cpp index dde78f6daa..07a218fe71 100644 --- a/src/modules/navigator/loiter.cpp +++ b/src/modules/navigator/loiter.cpp @@ -42,9 +42,9 @@ #include "loiter.h" #include "navigator.h" -Loiter::Loiter(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), - _param_yawmode(this, "MIS_YAWMODE", false) +Loiter::Loiter(Navigator *navigator) : + MissionBlock(navigator), + ModuleParams(navigator) { } diff --git a/src/modules/navigator/loiter.h b/src/modules/navigator/loiter.h index 84240bd552..2b63721e6c 100644 --- a/src/modules/navigator/loiter.h +++ b/src/modules/navigator/loiter.h @@ -44,10 +44,12 @@ #include "navigator_mode.h" #include "mission_block.h" -class Loiter final : public MissionBlock +#include + +class Loiter : public MissionBlock, public ModuleParams { public: - Loiter(Navigator *navigator, const char *name); + Loiter(Navigator *navigator); ~Loiter() = default; void on_inactive() override; @@ -75,7 +77,9 @@ private: */ void set_loiter_position(); - control::BlockParamInt _param_yawmode; + DEFINE_PARAMETERS( + (ParamInt) _param_yawmode + ) bool _loiter_pos_set{false}; }; diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index c1ed9a0820..bfe70f123d 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -59,13 +59,9 @@ #include #include -Mission::Mission(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), - _param_dist_1wp(this, "MIS_DIST_1WP", false), - _param_dist_between_wps(this, "MIS_DIST_WPS", false), - _param_altmode(this, "MIS_ALTMODE", false), - _param_yawmode(this, "MIS_YAWMODE", false), - _param_mnt_yaw_ctl(this, "MIS_MNT_YAW_CTL", false) +Mission::Mission(Navigator *navigator) : + MissionBlock(navigator), + ModuleParams(navigator) { } diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index e6493b869c..b881934eee 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -53,6 +53,7 @@ #include #include +#include #include #include #include @@ -64,10 +65,10 @@ class Navigator; -class Mission final : public MissionBlock +class Mission : public MissionBlock, public ModuleParams { public: - Mission(Navigator *navigator, const char *name); + Mission(Navigator *navigator); ~Mission() override = default; void on_inactive() override; @@ -227,11 +228,13 @@ private: */ bool find_offboard_land_start(); - control::BlockParamFloat _param_dist_1wp; - control::BlockParamFloat _param_dist_between_wps; - control::BlockParamInt _param_altmode; - control::BlockParamInt _param_yawmode; - control::BlockParamInt _param_mnt_yaw_ctl; + DEFINE_PARAMETERS( + (ParamFloat) _param_dist_1wp, + (ParamFloat) _param_dist_between_wps, + (ParamInt) _param_altmode, + (ParamInt) _param_yawmode, + (ParamInt) _param_mnt_yaw_ctl + ) struct mission_s _offboard_mission {}; diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index be8faf5ac8..ea85b7d017 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -54,8 +54,8 @@ #include #include -MissionBlock::MissionBlock(Navigator *navigator, const char *name) : - NavigatorMode(navigator, name) +MissionBlock::MissionBlock(Navigator *navigator) : + NavigatorMode(navigator) { } diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h index 13a4fc45fc..d7f454b712 100644 --- a/src/modules/navigator/mission_block.h +++ b/src/modules/navigator/mission_block.h @@ -44,8 +44,6 @@ #include "navigator_mode.h" #include "navigation.h" -#include -#include #include #include #include @@ -62,7 +60,7 @@ public: /** * Constructor */ - MissionBlock(Navigator *navigator, const char *name); + MissionBlock(Navigator *navigator); virtual ~MissionBlock() = default; MissionBlock(const MissionBlock &) = delete; diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 9c5a843286..15ab7eb406 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -56,9 +56,8 @@ #include "rtl.h" #include "takeoff.h" -#include -#include #include +#include #include #include #include @@ -80,7 +79,7 @@ #define NAVIGATOR_MODE_ARRAY_SIZE 11 -class Navigator : public control::SuperBlock +class Navigator : public ModuleParams { public: Navigator(); @@ -331,24 +330,27 @@ private: NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */ - // navigator parameters - control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */ - control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */ - control::BlockParamFloat _param_fw_alt_acceptance_radius; /**< acceptance radius for fixedwing altitude */ - control::BlockParamFloat _param_mc_alt_acceptance_radius; /**< acceptance radius for multicopter altitude */ - control::BlockParamInt _param_force_vtol; /**< acceptance radius for multicopter altitude */ - control::BlockParamInt _param_traffic_avoidance_mode; /**< avoiding other aircraft is enabled */ + DEFINE_PARAMETERS( + (ParamFloat) _param_loiter_radius, /**< loiter radius for fixedwing */ + (ParamFloat) _param_acceptance_radius, /**< acceptance for takeoff */ + (ParamFloat) + _param_fw_alt_acceptance_radius, /**< acceptance radius for fixedwing altitude */ + (ParamFloat) + _param_mc_alt_acceptance_radius, /**< acceptance radius for multicopter altitude */ + (ParamInt) _param_force_vtol, /**< acceptance radius for multicopter altitude */ + (ParamInt) _param_traffic_avoidance_mode, /**< avoiding other aircraft is enabled */ - // non-navigator parameters - // Mission (MIS_*) - control::BlockParamFloat _param_loiter_min_alt; - control::BlockParamFloat _param_takeoff_min_alt; - control::BlockParamFloat _param_yaw_timeout; - control::BlockParamFloat _param_yaw_err; + // non-navigator parameters + // Mission (MIS_*) + (ParamFloat) _param_loiter_min_alt, + (ParamFloat) _param_takeoff_min_alt, + (ParamFloat) _param_yaw_timeout, + (ParamFloat) _param_yaw_err, - // VTOL parameters TODO: get these out of navigator - control::BlockParamFloat _param_back_trans_dec_mss; - control::BlockParamFloat _param_reverse_delay; + // VTOL parameters TODO: get these out of navigator + (ParamFloat) _param_back_trans_dec_mss, + (ParamFloat) _param_reverse_delay + ) float _mission_cruising_speed_mc{-1.0f}; float _mission_cruising_speed_fw{-1.0f}; diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 77f8d2482b..331f01fe7f 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -84,34 +84,20 @@ Navigator *g_navigator; } Navigator::Navigator() : - SuperBlock(nullptr, "NAV"), + ModuleParams(nullptr), _loop_perf(perf_alloc(PC_ELAPSED, "navigator")), _geofence(this), - _mission(this, "MIS"), - _loiter(this, "LOI"), - _takeoff(this, "TKF"), - _land(this, "LND"), - _precland(this, "PLD"), - _rtl(this, "RTL"), - _rcLoss(this, "RCL"), - _dataLinkLoss(this, "DLL"), - _engineFailure(this, "EF"), - _gpsFailure(this, "GPSF"), - _follow_target(this, "TAR"), - // navigator params - _param_loiter_radius(this, "LOITER_RAD"), - _param_acceptance_radius(this, "ACC_RAD"), - _param_fw_alt_acceptance_radius(this, "FW_ALT_RAD"), - _param_mc_alt_acceptance_radius(this, "MC_ALT_RAD"), - _param_force_vtol(this, "FORCE_VT"), - _param_traffic_avoidance_mode(this, "TRAFF_AVOID"), - // non-navigator params - _param_loiter_min_alt(this, "MIS_LTRMIN_ALT", false), - _param_takeoff_min_alt(this, "MIS_TAKEOFF_ALT", false), - _param_yaw_timeout(this, "MIS_YAW_TMT", false), - _param_yaw_err(this, "MIS_YAW_ERR", false), - _param_back_trans_dec_mss(this, "VT_B_DEC_MSS", false), - _param_reverse_delay(this, "VT_B_REV_DEL", false) + _mission(this), + _loiter(this), + _takeoff(this), + _land(this), + _precland(this), + _rtl(this), + _rcLoss(this), + _dataLinkLoss(this), + _engineFailure(this), + _gpsFailure(this), + _follow_target(this) { /* Create a list of our possible navigation types */ _navigation_mode_array[0] = &_mission; diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp index dd57573ffe..2a3c5fd48e 100644 --- a/src/modules/navigator/navigator_mode.cpp +++ b/src/modules/navigator/navigator_mode.cpp @@ -42,8 +42,7 @@ #include "navigator_mode.h" #include "navigator.h" -NavigatorMode::NavigatorMode(Navigator *navigator, const char *name) : - Block(navigator, name), +NavigatorMode::NavigatorMode(Navigator *navigator) : _navigator(navigator), _active(false) { diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h index a99cfbd7a7..113a6f4a8f 100644 --- a/src/modules/navigator/navigator_mode.h +++ b/src/modules/navigator/navigator_mode.h @@ -42,15 +42,12 @@ #ifndef NAVIGATOR_MODE_H #define NAVIGATOR_MODE_H -#include -#include - class Navigator; -class NavigatorMode : public control::Block +class NavigatorMode { public: - NavigatorMode(Navigator *navigator, const char *name); + NavigatorMode(Navigator *navigator); virtual ~NavigatorMode() = default; NavigatorMode(const NavigatorMode &) = delete; NavigatorMode operator=(const NavigatorMode &) = delete; diff --git a/src/modules/navigator/precland.cpp b/src/modules/navigator/precland.cpp index cc5be68527..6819af668e 100644 --- a/src/modules/navigator/precland.cpp +++ b/src/modules/navigator/precland.cpp @@ -59,26 +59,16 @@ #define STATE_TIMEOUT 10000000 // [us] Maximum time to spend in any state -PrecLand::PrecLand(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), +PrecLand::PrecLand(Navigator *navigator) : + MissionBlock(navigator), + ModuleParams(navigator), _targetPoseSub(0), _target_pose_valid(false), _state_start_time(0), _search_cnt(0), - _approach_alt(0), - _param_timeout(this, "PLD_BTOUT", false), - _param_hacc_rad(this, "PLD_HACC_RAD", false), - _param_final_approach_alt(this, "PLD_FAPPR_ALT", false), - _param_search_alt(this, "PLD_SRCH_ALT", false), - _param_search_timeout(this, "PLD_SRCH_TOUT", false), - _param_max_searches(this, "PLD_MAX_SRCH", false), - _param_acceleration_hor(this, "MPC_ACC_HOR", false), - _param_xy_vel_cruise(this, "MPC_XY_CRUISE", false) + _approach_alt(0) { - /* load initial params */ - updateParams(); - } PrecLand::~PrecLand() diff --git a/src/modules/navigator/precland.h b/src/modules/navigator/precland.h index b8b9805e9a..b0122e6514 100644 --- a/src/modules/navigator/precland.h +++ b/src/modules/navigator/precland.h @@ -41,10 +41,10 @@ #ifndef NAVIGATOR_PRECLAND_H #define NAVIGATOR_PRECLAND_H -#include -#include -#include +#include #include +#include +#include #include "navigator_mode.h" #include "mission_block.h" @@ -64,10 +64,10 @@ enum class PrecLandMode { Required = 2 // try to find landing target if not visible at the beginning }; -class PrecLand : public MissionBlock +class PrecLand : public MissionBlock, public ModuleParams { public: - PrecLand(Navigator *navigator, const char *name); + PrecLand(Navigator *navigator); ~PrecLand(); @@ -121,14 +121,16 @@ private: PrecLandMode _mode; - control::BlockParamFloat _param_timeout; - control::BlockParamFloat _param_hacc_rad; - control::BlockParamFloat _param_final_approach_alt; - control::BlockParamFloat _param_search_alt; - control::BlockParamFloat _param_search_timeout; - control::BlockParamInt _param_max_searches; - control::BlockParamFloat _param_acceleration_hor; - control::BlockParamFloat _param_xy_vel_cruise; + DEFINE_PARAMETERS( + (ParamFloat) _param_timeout, + (ParamFloat) _param_hacc_rad, + (ParamFloat) _param_final_approach_alt, + (ParamFloat) _param_search_alt, + (ParamFloat) _param_search_timeout, + (ParamInt) _param_max_searches, + (ParamFloat) _param_acceleration_hor, + (ParamFloat) _param_xy_vel_cruise + ) }; diff --git a/src/modules/navigator/rcloss.cpp b/src/modules/navigator/rcloss.cpp index 8f0549781c..74ef1615e0 100644 --- a/src/modules/navigator/rcloss.cpp +++ b/src/modules/navigator/rcloss.cpp @@ -53,9 +53,9 @@ #include "navigator.h" #include "datalinkloss.h" -RCLoss::RCLoss(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), - _param_loitertime(this, "LT"), +RCLoss::RCLoss(Navigator *navigator) : + MissionBlock(navigator), + ModuleParams(navigator), _rcl_state(RCL_STATE_NONE) { } diff --git a/src/modules/navigator/rcloss.h b/src/modules/navigator/rcloss.h index 8f23d5ff88..c0c2ae02ce 100644 --- a/src/modules/navigator/rcloss.h +++ b/src/modules/navigator/rcloss.h @@ -40,15 +40,17 @@ #ifndef NAVIGATOR_RCLOSS_H #define NAVIGATOR_RCLOSS_H +#include + #include "navigator_mode.h" #include "mission_block.h" class Navigator; -class RCLoss final : public MissionBlock +class RCLoss : public MissionBlock, public ModuleParams { public: - RCLoss(Navigator *navigator, const char *name); + RCLoss(Navigator *navigator); ~RCLoss() = default; void on_inactive() override; @@ -56,8 +58,9 @@ public: void on_active() override; private: - /* Params */ - control::BlockParamFloat _param_loitertime; + DEFINE_PARAMETERS( + (ParamFloat) _param_loitertime + ) enum RCLState { RCL_STATE_NONE = 0, diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index 329f9e761a..2874bdbefe 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -50,13 +50,9 @@ using math::min; static constexpr float DELAY_SIGMA = 0.01f; -RTL::RTL(Navigator *navigator, const char *name) : - MissionBlock(navigator, name), - _param_return_alt(this, "RTL_RETURN_ALT", false), - _param_descend_alt(this, "RTL_DESCEND_ALT", false), - _param_land_delay(this, "RTL_LAND_DELAY", false), - _param_rtl_min_dist(this, "RTL_MIN_DIST", false), - _param_rtl_land_type(this, "RTL_LAND_TYPE", false) +RTL::RTL(Navigator *navigator) : + MissionBlock(navigator), + ModuleParams(navigator) { } diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h index b18d8254eb..9807d9c388 100644 --- a/src/modules/navigator/rtl.h +++ b/src/modules/navigator/rtl.h @@ -41,15 +41,17 @@ #ifndef NAVIGATOR_RTL_H #define NAVIGATOR_RTL_H +#include + #include "navigator_mode.h" #include "mission_block.h" class Navigator; -class RTL final : public MissionBlock +class RTL : public MissionBlock, public ModuleParams { public: - RTL(Navigator *navigator, const char *name); + RTL(Navigator *navigator); ~RTL() = default; void on_inactive() override; @@ -84,11 +86,13 @@ private: bool _rtl_alt_min{false}; - control::BlockParamFloat _param_return_alt; - control::BlockParamFloat _param_descend_alt; - control::BlockParamFloat _param_land_delay; - control::BlockParamFloat _param_rtl_min_dist; - control::BlockParamInt _param_rtl_land_type; + DEFINE_PARAMETERS( + (ParamFloat) _param_return_alt, + (ParamFloat) _param_descend_alt, + (ParamFloat) _param_land_delay, + (ParamFloat) _param_rtl_min_dist, + (ParamInt) _param_rtl_land_type + ) }; #endif diff --git a/src/modules/navigator/takeoff.cpp b/src/modules/navigator/takeoff.cpp index 94ce97213c..7b613edd7e 100644 --- a/src/modules/navigator/takeoff.cpp +++ b/src/modules/navigator/takeoff.cpp @@ -41,8 +41,8 @@ #include "takeoff.h" #include "navigator.h" -Takeoff::Takeoff(Navigator *navigator, const char *name) : - MissionBlock(navigator, name) +Takeoff::Takeoff(Navigator *navigator) : + MissionBlock(navigator) { } diff --git a/src/modules/navigator/takeoff.h b/src/modules/navigator/takeoff.h index 75913f8adc..c6d7a73876 100644 --- a/src/modules/navigator/takeoff.h +++ b/src/modules/navigator/takeoff.h @@ -31,7 +31,7 @@ * ****************************************************************************/ /** - * @file Takeoff.h + * @file takeoff.h * * Helper class to take off * @@ -41,8 +41,6 @@ #ifndef NAVIGATOR_TAKEOFF_H #define NAVIGATOR_TAKEOFF_H -#include -#include #include "navigator_mode.h" #include "mission_block.h" @@ -50,7 +48,7 @@ class Takeoff final : public MissionBlock { public: - Takeoff(Navigator *navigator, const char *name); + Takeoff(Navigator *navigator); ~Takeoff() = default; void on_activation() override;