mirror of https://github.com/ArduPilot/ardupilot
Copter: white space fixes
This commit is contained in:
parent
eee0f028ba
commit
c4b5d47e1f
|
@ -22,7 +22,7 @@
|
|||
* Based on code and ideas from the Arducopter team: Leonard Hall, Andrew Tridgell, Robert Lefebvre, Pat Hickey, Michael Oborne, Jani Hirvinen,
|
||||
Olivier Adler, Kevin Hester, Arthur Benemann, Jonathan Challinger, John Arne Birkeland,
|
||||
Jean-Louis Naudin, Mike Smith, and more
|
||||
* Thanks to: Chris Anderson, Jordi Munoz, Jason Short, Doug Weibel, Jose Julio
|
||||
* Thanks to: Chris Anderson, Jordi Munoz, Jason Short, Doug Weibel, Jose Julio
|
||||
*
|
||||
* Special Thanks to contributors (in alphabetical order by first name):
|
||||
*
|
||||
|
@ -37,7 +37,7 @@
|
|||
* Christof Schmid :Alpha testing
|
||||
* Craig Elder :Release Management, Support
|
||||
* Dani Saez :V Octo Support
|
||||
* Doug Weibel :DCM, Libraries, Control law advice
|
||||
* Doug Weibel :DCM, Libraries, Control law advice
|
||||
* Emile Castelnuovo :VRBrain port, bug fixes
|
||||
* Gregory Fletcher :Camera mount orientation math
|
||||
* Guntars :Arming safety suggestion
|
||||
|
@ -48,7 +48,7 @@
|
|||
* James Goppert :Mavlink Support
|
||||
* Jani Hiriven :Testing feedback
|
||||
* Jean-Louis Naudin :Auto Landing
|
||||
* John Arne Birkeland :PPM Encoder
|
||||
* John Arne Birkeland :PPM Encoder
|
||||
* Jose Julio :Stabilization Control laws, MPU6k driver
|
||||
* Julien Dubois :PosHold flight mode
|
||||
* Julian Oes :Pixhawk
|
||||
|
|
|
@ -479,9 +479,9 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
GOBJECT(relay, "RELAY_", AP_Relay),
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
// @Group: CHUTE_
|
||||
// @Group: CHUTE_
|
||||
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
|
||||
GOBJECT(parachute, "CHUTE_", AP_Parachute),
|
||||
GOBJECT(parachute, "CHUTE_", AP_Parachute),
|
||||
#endif
|
||||
|
||||
// @Group: LGR_
|
||||
|
|
|
@ -27,20 +27,20 @@ public:
|
|||
// Parameter identities.
|
||||
//
|
||||
// The enumeration defined here is used to ensure that every parameter
|
||||
// or parameter group has a unique ID number. This number is used by
|
||||
// or parameter group has a unique ID number. This number is used by
|
||||
// AP_Param to store and locate parameters in EEPROM.
|
||||
//
|
||||
// Note that entries without a number are assigned the next number after
|
||||
// the entry preceding them. When adding new entries, ensure that they
|
||||
// the entry preceding them. When adding new entries, ensure that they
|
||||
// don't overlap.
|
||||
//
|
||||
// Try to group related variables together, and assign them a set
|
||||
// range in the enumeration. Place these groups in numerical order
|
||||
// range in the enumeration. Place these groups in numerical order
|
||||
// at the end of the enumeration.
|
||||
//
|
||||
// WARNING: Care should be taken when editing this enumeration as the
|
||||
// AP_Param load/save code depends on the values here to identify
|
||||
// variables saved in EEPROM.
|
||||
// AP_Param load/save code depends on the values here to identify
|
||||
// variables saved in EEPROM.
|
||||
//
|
||||
//
|
||||
enum {
|
||||
|
@ -94,7 +94,7 @@ public:
|
|||
// with next eeprom number
|
||||
// change
|
||||
k_param_toy_yaw_rate, // deprecated - remove
|
||||
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
|
||||
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
|
||||
k_param_rssi_pin, // unused, replaced by rssi_ library parameters
|
||||
k_param_throttle_accel_enabled, // deprecated - remove
|
||||
k_param_wp_yaw_behavior,
|
||||
|
@ -253,10 +253,10 @@ public:
|
|||
// 160: Navigation parameters
|
||||
//
|
||||
k_param_rtl_altitude = 160,
|
||||
k_param_crosstrack_gain, // deprecated - remove with next eeprom number change
|
||||
k_param_crosstrack_gain, // deprecated - remove with next eeprom number change
|
||||
k_param_rtl_loiter_time,
|
||||
k_param_rtl_alt_final,
|
||||
k_param_tilt_comp, //164 deprecated - remove with next eeprom number change
|
||||
k_param_tilt_comp, // 164 deprecated - remove with next eeprom number change
|
||||
|
||||
|
||||
//
|
||||
|
|
|
@ -513,7 +513,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
|||
do_aux_function_change_mode(Mode::Number::ALT_HOLD, ch_flag);
|
||||
break;
|
||||
|
||||
case AUX_FUNC::FLOWHOLD:
|
||||
case AUX_FUNC::FLOWHOLD:
|
||||
#if OPTFLOW == ENABLED
|
||||
do_aux_function_change_mode(Mode::Number::FLOWHOLD, ch_flag);
|
||||
#endif
|
||||
|
|
|
@ -537,7 +537,7 @@
|
|||
#endif
|
||||
|
||||
#ifndef RTL_ALT
|
||||
# define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude
|
||||
# define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude
|
||||
#endif
|
||||
|
||||
#ifndef RTL_ALT_MIN
|
||||
|
|
|
@ -153,7 +153,7 @@ void Copter::thrust_loss_check()
|
|||
// called at MAIN_LOOP_RATE
|
||||
void Copter::parachute_check()
|
||||
{
|
||||
static uint16_t control_loss_count; // number of iterations we have been out of control
|
||||
static uint16_t control_loss_count; // number of iterations we have been out of control
|
||||
static int32_t baro_alt_start;
|
||||
|
||||
// exit immediately if parachute is not enabled
|
||||
|
|
|
@ -409,7 +409,7 @@ void Mode::get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, floa
|
|||
roll_out = channel_roll->get_control_in();
|
||||
pitch_out = channel_pitch->get_control_in();
|
||||
|
||||
// limit max lean angle
|
||||
// limit max lean angle
|
||||
angle_limit = constrain_float(angle_limit, 1000.0f, angle_max);
|
||||
|
||||
// scale roll and pitch inputs to ANGLE_MAX parameter range
|
||||
|
|
|
@ -1053,7 +1053,7 @@ Location ModeAuto::terrain_adjusted_location(const AP_Mission::Mission_Command&
|
|||
}
|
||||
|
||||
/********************************************************************************/
|
||||
// Nav (Must) commands
|
||||
// Nav (Must) commands
|
||||
/********************************************************************************/
|
||||
|
||||
// do_takeoff - initiate takeoff navigation command
|
||||
|
@ -1343,7 +1343,7 @@ void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)
|
|||
}
|
||||
|
||||
/********************************************************************************/
|
||||
// Condition (May) commands
|
||||
// Condition (May) commands
|
||||
/********************************************************************************/
|
||||
|
||||
void ModeAuto::do_wait_delay(const AP_Mission::Mission_Command& cmd)
|
||||
|
@ -1359,15 +1359,15 @@ void ModeAuto::do_within_distance(const AP_Mission::Mission_Command& cmd)
|
|||
|
||||
void ModeAuto::do_yaw(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
auto_yaw.set_fixed_yaw(
|
||||
cmd.content.yaw.angle_deg,
|
||||
cmd.content.yaw.turn_rate_dps,
|
||||
cmd.content.yaw.direction,
|
||||
cmd.content.yaw.relative_angle > 0);
|
||||
auto_yaw.set_fixed_yaw(
|
||||
cmd.content.yaw.angle_deg,
|
||||
cmd.content.yaw.turn_rate_dps,
|
||||
cmd.content.yaw.direction,
|
||||
cmd.content.yaw.relative_angle > 0);
|
||||
}
|
||||
|
||||
/********************************************************************************/
|
||||
// Do (Now) commands
|
||||
// Do (Now) commands
|
||||
/********************************************************************************/
|
||||
|
||||
|
||||
|
@ -1401,7 +1401,7 @@ void ModeAuto::do_set_home(const AP_Mission::Mission_Command& cmd)
|
|||
// do_roi - starts actions required by MAV_CMD_DO_SET_ROI
|
||||
// this involves either moving the camera to point at the ROI (region of interest)
|
||||
// and possibly rotating the copter to point at the ROI if our mount type does not support a yaw feature
|
||||
// TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
|
||||
// TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
|
||||
void ModeAuto::do_roi(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
auto_yaw.set_roi(cmd.content.location);
|
||||
|
@ -1471,7 +1471,7 @@ void ModeAuto::do_RTL(void)
|
|||
}
|
||||
|
||||
/********************************************************************************/
|
||||
// Verify Nav (Must) commands
|
||||
// Verify Nav (Must) commands
|
||||
/********************************************************************************/
|
||||
|
||||
// verify_takeoff - check if we have completed the takeoff
|
||||
|
@ -1778,18 +1778,18 @@ bool ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
// start timer if necessary
|
||||
if (loiter_time == 0) {
|
||||
loiter_time = millis();
|
||||
if (loiter_time_max > 0) {
|
||||
// play a tone
|
||||
AP_Notify::events.waypoint_complete = 1;
|
||||
}
|
||||
if (loiter_time_max > 0) {
|
||||
// play a tone
|
||||
AP_Notify::events.waypoint_complete = 1;
|
||||
}
|
||||
}
|
||||
|
||||
// check if timer has run out
|
||||
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
|
||||
if (loiter_time_max == 0) {
|
||||
// play a tone
|
||||
AP_Notify::events.waypoint_complete = 1;
|
||||
}
|
||||
if (loiter_time_max == 0) {
|
||||
// play a tone
|
||||
AP_Notify::events.waypoint_complete = 1;
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -907,15 +907,15 @@ void ToyMode::blink_update(void)
|
|||
if (copter.motors->armed() && AP_Notify::flags.failsafe_battery) {
|
||||
pattern = BLINK_8;
|
||||
} else if (!copter.motors->armed() && (blink_disarm > 0)) {
|
||||
pattern = BLINK_8;
|
||||
blink_disarm--;
|
||||
} else {
|
||||
pattern = BLINK_8;
|
||||
blink_disarm--;
|
||||
} else {
|
||||
pattern = BLINK_FULL;
|
||||
}
|
||||
|
||||
if (copter.motors->armed()) {
|
||||
blink_disarm = 4;
|
||||
}
|
||||
blink_disarm = 4;
|
||||
}
|
||||
|
||||
if (red_blink_count == 0) {
|
||||
red_blink_pattern = pattern;
|
||||
|
|
Loading…
Reference in New Issue