mirror of https://github.com/ArduPilot/ardupilot
removed unused functions, log fix
This commit is contained in:
parent
d8361dfe67
commit
2c9ebf11b8
|
@ -779,7 +779,8 @@ static void Log_Read_Performance()
|
|||
temp2,
|
||||
temp3,
|
||||
temp4,
|
||||
temp5);
|
||||
temp5,
|
||||
temp6);
|
||||
}
|
||||
|
||||
// Write a command processing packet.
|
||||
|
|
|
@ -129,7 +129,7 @@ static int32_t read_alt_to_hold()
|
|||
// It's not currently used
|
||||
//********************************************************************************
|
||||
|
||||
static Location get_LOITER_home_wp()
|
||||
/*static Location get_LOITER_home_wp()
|
||||
{
|
||||
//so we know where we are navigating from
|
||||
next_WP = current_loc;
|
||||
|
@ -140,7 +140,7 @@ static Location get_LOITER_home_wp()
|
|||
temp.alt = read_alt_to_hold();
|
||||
return temp;
|
||||
}
|
||||
|
||||
*/
|
||||
/*
|
||||
This function sets the next waypoint command
|
||||
It precalculates all the necessary stuff.
|
||||
|
|
|
@ -1037,7 +1037,7 @@ static void fake_out_gps()
|
|||
}
|
||||
|
||||
*/
|
||||
|
||||
/*
|
||||
static void print_motor_out(){
|
||||
Serial.printf("out: R: %d, L: %d F: %d B: %d\n",
|
||||
(motor_out[CH_1] - g.rc_3.radio_min),
|
||||
|
@ -1045,5 +1045,5 @@ static void print_motor_out(){
|
|||
(motor_out[CH_3] - g.rc_3.radio_min),
|
||||
(motor_out[CH_4] - g.rc_3.radio_min));
|
||||
}
|
||||
|
||||
*/
|
||||
#endif // CLI_ENABLED
|
||||
|
|
Loading…
Reference in New Issue