From 3f773809c4f3ecd6146c1f5f0b15c1b02eb6f245 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 25 Nov 2022 12:08:04 +0100 Subject: [PATCH] LaunchDetection: fix code style (name class members with trailing underscore) And also align parameter handle name to real parameter name. Signed-off-by: Silvan Fuhrer --- .../launchdetection/LaunchDetector.cpp | 24 +++++++++---------- .../launchdetection/LaunchDetector.h | 8 +++---- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/modules/fw_pos_control_l1/launchdetection/LaunchDetector.cpp b/src/modules/fw_pos_control_l1/launchdetection/LaunchDetector.cpp index 4ccfcd2dea..d84178c371 100644 --- a/src/modules/fw_pos_control_l1/launchdetection/LaunchDetector.cpp +++ b/src/modules/fw_pos_control_l1/launchdetection/LaunchDetector.cpp @@ -51,26 +51,26 @@ void LaunchDetector::update(const float dt, const float accel_x, orb_advert_t * switch (state_) { case launch_detection_status_s::STATE_WAITING_FOR_LAUNCH: - _info_delay_counter_s_ += dt; + info_delay_counter_s_ += dt; /* Inform user that launchdetection is running every kInfoDelay seconds */ - if (_info_delay_counter_s_ >= kInfoDelay) { + if (info_delay_counter_s_ >= kInfoDelay) { mavlink_log_info(mavlink_log_pub, "Launch detection running\t"); events::send(events::ID("launch_detection_running_info"), events::Log::Info, "Launch detection running"); - _info_delay_counter_s_ = 0.f; // reset counter + info_delay_counter_s_ = 0.f; // reset counter } /* Detect a acceleration that is longer and stronger as the minimum given by the params */ - if (accel_x > _param_laun_cat_a.get()) { + if (accel_x > param_fw_laun_ac_thld_.get()) { acceleration_detected_counter_ += dt; - if (acceleration_detected_counter_ > _param_laun_cat_t.get()) { - if (_param_laun_cat_mdel.get() > 0.f) { + if (acceleration_detected_counter_ > param_fw_laun_ac_t_.get()) { + if (param_fw_laun_mot_del_.get() > 0.f) { state_ = launch_detection_status_s::STATE_LAUNCH_DETECTED_DISABLED_MOTOR; mavlink_log_info(mavlink_log_pub, "Launch detected: enable control, waiting %8.1fs until throttling up\t", - (double)_param_laun_cat_mdel.get()); + (double)param_fw_laun_mot_del_.get()); events::send(events::ID("launch_detection_wait_for_throttle"), {events::Log::Info, events::LogInternal::Info}, - "Launch detected: enablecontrol, waiting {1:.1}s until full throttle", (double)_param_laun_cat_mdel.get()); + "Launch detected: enablecontrol, waiting {1:.1}s until full throttle", (double)param_fw_laun_mot_del_.get()); } else { /* No motor delay set: go directly to enablemotors state */ @@ -92,19 +92,19 @@ void LaunchDetector::update(const float dt, const float accel_x, orb_advert_t * * over to allow full throttle */ motor_delay_counter_ += dt; - if (motor_delay_counter_ > _param_laun_cat_mdel.get()) { + if (motor_delay_counter_ > param_fw_laun_mot_del_.get()) { mavlink_log_info(mavlink_log_pub, "Launch detected: enable motors\t"); events::send(events::ID("launch_detection_enable_motors"), {events::Log::Info, events::LogInternal::Info}, "Launch detected: enable motors"); state_ = launch_detection_status_s::STATE_FLYING; } - _info_delay_counter_s_ = kInfoDelay; // reset counter + info_delay_counter_s_ = kInfoDelay; // reset counter break; default: // state flying - _info_delay_counter_s_ = kInfoDelay; // reset counter + info_delay_counter_s_ = kInfoDelay; // reset counter break; } @@ -117,7 +117,7 @@ uint LaunchDetector::getLaunchDetected() const void LaunchDetector::reset() { - _info_delay_counter_s_ = 0.f; + info_delay_counter_s_ = 0.f; acceleration_detected_counter_ = 0.f; motor_delay_counter_ = 0.f; state_ = launch_detection_status_s::STATE_WAITING_FOR_LAUNCH; diff --git a/src/modules/fw_pos_control_l1/launchdetection/LaunchDetector.h b/src/modules/fw_pos_control_l1/launchdetection/LaunchDetector.h index 621197f708..53e568006f 100644 --- a/src/modules/fw_pos_control_l1/launchdetection/LaunchDetector.h +++ b/src/modules/fw_pos_control_l1/launchdetection/LaunchDetector.h @@ -94,7 +94,7 @@ private: /** * Info delay counter (to publish info every kInfoDelay seconds) [s] */ - float _info_delay_counter_s_{kInfoDelay}; + float info_delay_counter_s_{kInfoDelay}; /** * Counter for how long the measured acceleration is above the defined threshold [s] @@ -107,9 +107,9 @@ private: uint state_{launch_detection_status_s::STATE_WAITING_FOR_LAUNCH}; DEFINE_PARAMETERS( - (ParamFloat) _param_laun_cat_a, - (ParamFloat) _param_laun_cat_t, - (ParamFloat) _param_laun_cat_mdel + (ParamFloat) param_fw_laun_ac_thld_, + (ParamFloat) param_fw_laun_ac_t_, + (ParamFloat) param_fw_laun_mot_del_ ) };