From 0056bfadd7babe1c298e4ee76cb18fec7126b14e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 25 Jan 2013 23:25:31 +0900 Subject: [PATCH] Copter: rename ROLL_PITCH_LOITER new name ROLL_PITCH_LOITER_INAV makes it more clear that it should only be used with the new inertial nav loiter controllers --- ArduCopter/ArduCopter.pde | 4 ++-- ArduCopter/defines.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index e1baed8074..8369dcaa9c 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1601,7 +1601,7 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode) roll_pitch_initialised = true; break; - case ROLL_PITCH_LOITER: + case ROLL_PITCH_LOITER_INAV: // require gps lock if( ap.home_is_set ) { roll_pitch_initialised = true; @@ -1712,7 +1712,7 @@ void update_roll_pitch_mode(void) roll_pitch_toy(); break; - case ROLL_PITCH_LOITER: + case ROLL_PITCH_LOITER_INAV: // apply SIMPLE mode transform if(ap.simple_mode && ap_system.new_radio_frame) { update_simple_mode(); diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index fa7d14914b..543320e1f1 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -30,7 +30,7 @@ #define ROLL_PITCH_AUTO 2 #define ROLL_PITCH_STABLE_OF 3 #define ROLL_PITCH_TOY 4 // THOR This is the Roll and Pitch mode -#define ROLL_PITCH_LOITER 5 // pilot inputs the desired horizontal velocities +#define ROLL_PITCH_LOITER_INAV 5 // pilot inputs the desired horizontal velocities #define THROTTLE_MANUAL 0 // manual throttle mode - pilot input goes directly to motors #define THROTTLE_MANUAL_TILT_COMPENSATED 1 // mostly manual throttle but with some tilt compensation