From 5107cb495a08b3a34c1a6e5c81bd0d29743627b2 Mon Sep 17 00:00:00 2001 From: muramura Date: Mon, 29 Apr 2024 02:30:30 +0900 Subject: [PATCH] Copter: Change the sub-mode description --- ArduCopter/mode_guided.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 8ea52985fd..35df242985 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -243,10 +243,10 @@ void ModeGuided::pos_control_start() pva_control_start(); } -// initialise guided mode's velocity controller +// initialise guided mode's acceleration controller void ModeGuided::accel_control_start() { - // set guided_mode to velocity controller + // set guided_mode to acceleration controller guided_mode = SubMode::Accel; // initialise position controller @@ -256,7 +256,7 @@ void ModeGuided::accel_control_start() // initialise guided mode's velocity and acceleration controller void ModeGuided::velaccel_control_start() { - // set guided_mode to velocity controller + // set guided_mode to velocity and acceleration controller guided_mode = SubMode::VelAccel; // initialise position controller @@ -266,7 +266,7 @@ void ModeGuided::velaccel_control_start() // initialise guided mode's position, velocity and acceleration controller void ModeGuided::posvelaccel_control_start() { - // set guided_mode to velocity controller + // set guided_mode to position, velocity and acceleration controller guided_mode = SubMode::PosVelAccel; // initialise position controller @@ -515,7 +515,7 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y // set_velaccel - sets guided mode's target velocity and acceleration void ModeGuided::set_accel(const Vector3f& acceleration, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool log_request) { - // check we are in velocity control mode + // check we are in acceleration control mode if (guided_mode != SubMode::Accel) { accel_control_start(); } @@ -547,7 +547,7 @@ void ModeGuided::set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_ // set_velaccel - sets guided mode's target velocity and acceleration void ModeGuided::set_velaccel(const Vector3f& velocity, const Vector3f& acceleration, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool log_request) { - // check we are in velocity control mode + // check we are in velocity and acceleration control mode if (guided_mode != SubMode::VelAccel) { velaccel_control_start(); } @@ -589,7 +589,7 @@ bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const } #endif - // check we are in velocity control mode + // check we are in position, velocity and acceleration control mode if (guided_mode != SubMode::PosVelAccel) { posvelaccel_control_start(); }