mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-25 09:13:57 -04:00
Cosmetic changes
GPS LED lock waits for home_is_set to be true
This commit is contained in:
parent
326a663c6b
commit
d1fcebb5ca
@ -325,9 +325,6 @@ static int16_t y_actual_speed;
|
||||
static int16_t x_rate_error;
|
||||
static int16_t y_rate_error;
|
||||
|
||||
//static int16_t my_max_speed; // used for debugging logs
|
||||
//static int16_t target_x_rate;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Radio
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -1883,6 +1880,7 @@ adjust_altitude()
|
||||
manual_boost = g.rc_3.control_in - 180;
|
||||
manual_boost = max(-120, manual_boost);
|
||||
update_throttle_cruise();
|
||||
|
||||
}else if (g.rc_3.control_in >= 650){
|
||||
// we add 0 to 100 PWM to hover
|
||||
manual_boost = g.rc_3.control_in - 650;
|
||||
|
@ -4,8 +4,9 @@
|
||||
|
||||
static void init_camera()
|
||||
{
|
||||
APM_RC.enable_out(CH_CAM_PITCH);
|
||||
APM_RC.enable_out(CH_CAM_ROLL);
|
||||
APM_RC.enable_out(CH_CAM_PITCH);
|
||||
APM_RC.enable_out(CH_CAM_ROLL);
|
||||
|
||||
// ch 6 high(right) is down.
|
||||
g.rc_camera_pitch.set_angle(4500);
|
||||
g.rc_camera_roll.set_angle(4500);
|
||||
|
@ -154,7 +154,6 @@ static void read_trim_switch()
|
||||
// 1 = takeoff
|
||||
// 2 = WP 2
|
||||
// 3 = command total
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -19,7 +19,11 @@ static void update_GPS_light(void)
|
||||
switch (g_gps->status()){
|
||||
|
||||
case(2):
|
||||
digitalWrite(C_LED_PIN, LED_ON); //Turn LED C on when gps has valid fix.
|
||||
if(home_is_set) { // JLN update
|
||||
digitalWrite(C_LED_PIN, LED_ON); //Turn LED C on when gps has valid fix AND home is set.
|
||||
} else {
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
}
|
||||
break;
|
||||
|
||||
case(1):
|
||||
|
@ -1,7 +1,7 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
// 10 = 1 second
|
||||
#define ARM_DELAY 30
|
||||
#define ARM_DELAY 20
|
||||
#define DISARM_DELAY 20
|
||||
#define LEVEL_DELAY 100
|
||||
|
||||
|
@ -1096,7 +1096,7 @@ static void print_enabled(boolean b)
|
||||
static void
|
||||
init_esc()
|
||||
{
|
||||
motors_output_enable();
|
||||
motors_output_enable();
|
||||
while(1){
|
||||
read_radio();
|
||||
delay(100);
|
||||
|
Loading…
Reference in New Issue
Block a user