From 10a50dd97e2bfcbac0290db45c16a4ee695d05ff Mon Sep 17 00:00:00 2001 From: Dennis Mannhart Date: Thu, 21 Dec 2017 09:57:57 +0100 Subject: [PATCH] FlightTaskManual: switch to camel case --- .../tasks/FlightTaskManualAltitude.cpp | 16 ++++++++-------- .../tasks/FlightTaskManualAltitude.hpp | 8 ++++---- .../tasks/FlightTaskManualPosition.cpp | 18 +++++++++--------- .../tasks/FlightTaskManualPosition.hpp | 6 +++--- 4 files changed, 24 insertions(+), 24 deletions(-) diff --git a/src/lib/FlightTasks/tasks/FlightTaskManualAltitude.cpp b/src/lib/FlightTasks/tasks/FlightTaskManualAltitude.cpp index 7c157b0e70..0b826fd55e 100644 --- a/src/lib/FlightTasks/tasks/FlightTaskManualAltitude.cpp +++ b/src/lib/FlightTasks/tasks/FlightTaskManualAltitude.cpp @@ -61,7 +61,7 @@ bool FlightTaskManualAltitude::activate() return FlightTaskManual::activate(); } -void FlightTaskManualAltitude::scale_sticks() +void FlightTaskManualAltitude::scaleSticks() { /* map stick to velocity */ @@ -71,7 +71,7 @@ void FlightTaskManualAltitude::scale_sticks() } -void FlightTaskManualAltitude::update_heading_setpoints() +void FlightTaskManualAltitude::updateHeadingSetpoints() { if (fabsf(_sticks(3)) < FLT_EPSILON) { /* want to hold yaw */ @@ -85,7 +85,7 @@ void FlightTaskManualAltitude::update_heading_setpoints() } } -void FlightTaskManualAltitude::update_z_setpoints() +void FlightTaskManualAltitude::updateZsetpoints() { if (fabsf(_sticks(2)) < FLT_EPSILON) { /* want to hold altitude */ @@ -99,16 +99,16 @@ void FlightTaskManualAltitude::update_z_setpoints() } } -void FlightTaskManualAltitude::update_setpoints() +void FlightTaskManualAltitude::updateSetpoints() { - update_heading_setpoints(); - update_z_setpoints(); + updateHeadingSetpoints(); + updateZsetpoints(); } bool FlightTaskManualAltitude::update() { - scale_sticks(); - update_setpoints(); + scaleSticks(); + updateSetpoints(); _setPositionSetpoint(Vector3f(NAN, NAN, _pos_sp_z)); diff --git a/src/lib/FlightTasks/tasks/FlightTaskManualAltitude.hpp b/src/lib/FlightTasks/tasks/FlightTaskManualAltitude.hpp index 7b5f11f5a2..50edac664c 100644 --- a/src/lib/FlightTasks/tasks/FlightTaskManualAltitude.hpp +++ b/src/lib/FlightTasks/tasks/FlightTaskManualAltitude.hpp @@ -64,12 +64,12 @@ protected: control::BlockParamFloat _vel_max_up; /**< maximum speed allowed to go down */ control::BlockParamFloat _yaw_rate_scaling; /**< scaling factor from stick to yaw rate */ - virtual void update_setpoints(); /**< updates all setpoints */ - virtual void scale_sticks(); /**< scales sticks to velocity */ + virtual void updateSetpoints(); /**< updates all setpoints */ + virtual void scaleSticks(); /**< scales sticks to velocity */ private: - void update_heading_setpoints(); /**< sets yaw or yaw speed */ - void update_z_setpoints(); /**< sets position or velocity setpoint */ + void updateHeadingSetpoints(); /**< sets yaw or yaw speed */ + void updateZsetpoints(); /**< sets position or velocity setpoint */ float _pos_sp_predicted{0.0f}; /**< position setpoint computed in set_z_setpoints */ float _yaw_sp_predicted{0.0f}; /**< yaw setpoint computed in set_heading_setpoints */ diff --git a/src/lib/FlightTasks/tasks/FlightTaskManualPosition.cpp b/src/lib/FlightTasks/tasks/FlightTaskManualPosition.cpp index 7f64958457..570f1ae858 100644 --- a/src/lib/FlightTasks/tasks/FlightTaskManualPosition.cpp +++ b/src/lib/FlightTasks/tasks/FlightTaskManualPosition.cpp @@ -57,10 +57,10 @@ bool FlightTaskManualPosition::activate() return FlightTaskManualAltitude::activate(); } -void FlightTaskManualPosition::scale_sticks() +void FlightTaskManualPosition::scaleSticks() { /* scale all sticks including altitude and yaw */ - FlightTaskManualAltitude::scale_sticks(); + FlightTaskManualAltitude::scaleSticks(); matrix::Vector2f stick_xy(_sticks_expo(0), _sticks_expo(1)); @@ -76,7 +76,7 @@ void FlightTaskManualPosition::scale_sticks() } -void FlightTaskManualPosition::update_xy_setpoints() +void FlightTaskManualPosition::updateXYsetpoints() { matrix::Vector2f stick_xy(_sticks_expo(0), _sticks_expo(1)); @@ -92,21 +92,21 @@ void FlightTaskManualPosition::update_xy_setpoints() } } -void FlightTaskManualPosition::update_setpoints() +void FlightTaskManualPosition::updateSetpoints() { /* scale all sticks */ - scale_sticks(); + scaleSticks(); /* update all setpoints */ - FlightTaskManualAltitude::update_setpoints(); - update_xy_setpoints(); + FlightTaskManualAltitude::updateSetpoints(); + updateXYsetpoints(); } bool FlightTaskManualPosition::update() { - scale_sticks(); - update_setpoints(); + scaleSticks(); + updateSetpoints(); _setPositionSetpoint(Vector3f(_pos_sp_xy(0), _pos_sp_xy(1), _pos_sp_z)); _setVelocitySetpoint(Vector3f(_vel_sp_xy(0), _vel_sp_xy(1), _vel_sp_z)); diff --git a/src/lib/FlightTasks/tasks/FlightTaskManualPosition.hpp b/src/lib/FlightTasks/tasks/FlightTaskManualPosition.hpp index 1c7c7d04eb..e80e4ffcf4 100644 --- a/src/lib/FlightTasks/tasks/FlightTaskManualPosition.hpp +++ b/src/lib/FlightTasks/tasks/FlightTaskManualPosition.hpp @@ -59,11 +59,11 @@ protected: control::BlockParamFloat _vel_xy_manual_max; /**< maximum speed allowed horizontally */ - void update_setpoints() override; - void scale_sticks() override; + void updateSetpoints() override; + void scaleSticks() override; private: - void update_xy_setpoints(); + void updateXYsetpoints(); matrix::Vector2f _pos_sp_predicted{}; /**< position setpoint computed in set_xy_setpoints */