mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
Arducopter: Release 2.7.2
This commit is contained in:
parent
f4334c9aaf
commit
274b2e2143
@ -1,8 +1,8 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
#define THISFIRMWARE "ArduCopter V2.7.2 Gamma"
|
#define THISFIRMWARE "ArduCopter V2.7.2"
|
||||||
/*
|
/*
|
||||||
* ArduCopter Version 2.7 Gamma
|
* ArduCopter Version 2.7.2
|
||||||
* Lead author: Jason Short
|
* Lead author: Jason Short
|
||||||
* Based on code and ideas from the Arducopter team: Randy Mackay, Pat Hickey, Jose Julio, Jani Hirvinen, Andrew Tridgell, Justin Beech, Adam Rivera, Jean-Louis Naudin, Roberto Navoni
|
* Based on code and ideas from the Arducopter team: Randy Mackay, Pat Hickey, Jose Julio, Jani Hirvinen, Andrew Tridgell, Justin Beech, Adam Rivera, Jean-Louis Naudin, Roberto Navoni
|
||||||
* Thanks to: Chris Anderson, Mike Smith, Jordi Munoz, Doug Weibel, James Goppert, Benjamin Pelletier, Robert Lefebvre, Marco Robustini
|
* Thanks to: Chris Anderson, Mike Smith, Jordi Munoz, Doug Weibel, James Goppert, Benjamin Pelletier, Robert Lefebvre, Marco Robustini
|
||||||
|
@ -698,7 +698,7 @@
|
|||||||
// Stabilize Rate Control
|
// Stabilize Rate Control
|
||||||
//
|
//
|
||||||
#ifndef RATE_ROLL_P
|
#ifndef RATE_ROLL_P
|
||||||
# define RATE_ROLL_P 0.165
|
# define RATE_ROLL_P 0.175
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_I
|
#ifndef RATE_ROLL_I
|
||||||
# define RATE_ROLL_I 0.0
|
# define RATE_ROLL_I 0.0
|
||||||
@ -711,7 +711,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RATE_PITCH_P
|
#ifndef RATE_PITCH_P
|
||||||
# define RATE_PITCH_P 0.165
|
# define RATE_PITCH_P 0.175
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_I
|
#ifndef RATE_PITCH_I
|
||||||
# define RATE_PITCH_I 0.0
|
# define RATE_PITCH_I 0.0
|
||||||
|
Loading…
Reference in New Issue
Block a user