Commit Graph

476 Commits

Author SHA1 Message Date
Randy Mackay 566daf883a Copter: remove unused MODE bit from LOG_BITMASK
We always log the mode so no need for this bit
2013-05-17 12:26:42 +09:00
Randy Mackay 1426f40319 Copter: remove unused JDrones motor PID overrides 2013-05-17 12:05:20 +09:00
Randy Mackay e843bf3dfd Copter: bug fix for POSITION mode throttle
Was using alt-hold throttle controller instead of manual throttle
controller
2013-05-14 11:56:09 +09:00
Randy Mackay a2e298bbfc Copter: change to default RTL yaw behaviour
We will not point the nose home for RTL but will point the nose for all
other waypoints
2013-05-14 11:52:39 +09:00
Andrew Tridgell 0d027b7a23 Copter: updates for new compass API 2013-05-02 12:48:14 +10:00
Randy Mackay bab9fa25e5 Copter: add GCS failsafe 2013-04-29 21:30:22 +09:00
Randy Mackay 58d1da2d80 Copter: integrate AC_Fence in place of limits
Lesser functionality than limits but saves more than 150 bytes and it
works
2013-04-27 11:14:07 +09:00
Randy Mackay 94d4ecef11 Copter: reduce throttle rate D to zero 2013-04-21 16:28:07 +09:00
Bill Bonney 36041bb9ff Copter: Enable CURRENT logging by default to dataflash 2013-04-21 07:25:34 +10:00
Randy Mackay 745df9b13c Copter: add SONAR_GAIN to tune reaction to sonar
Some users report the response to sonar is too violent, this allows that
reaction to be reduced
2013-04-20 15:58:36 +09:00
Randy Mackay a53e5f747b Copter: add fourth yaw behaviour, look-at-home
Added get_wp_yaw_mode to remove duplication of checks of the
WP_YAW_BEHAVIOR parameter
2013-04-20 15:36:24 +09:00
Randy Mackay 37abfdc65a Copter: make CIRCLE_RATE a tunable parameter
Also bug fix to check of how many time it has rotated during a loiter
turns mission command
2013-04-20 12:03:55 +09:00
Randy Mackay 18c1373847 Copter: remove unused AUTO_VELZ defaults
These have now moved to AC_WPNav
2013-04-18 14:57:08 +09:00
Randy Mackay 82989d85f2 Copter: remove unused #defines 2013-04-16 22:34:12 +09:00
Randy Mackay 0663da7c9e Copter: loiter rate IMAX to 4m/s/s and D to zero 2013-04-16 22:28:18 +09:00
Randy Mackay 629d23b7e2 Copter: remove WP_SPEED and WP_RADIUS parameters
AC_WPNav library has equivalent params with very similar names
2013-04-14 13:27:37 +09:00
Randy Mackay 366616e32c Copter: reduce default loiter PIDs 2013-04-14 10:39:28 +09:00
Randy Mackay 1516972eaa Copter: add panorama to CIRCLE mode
Yaw will slowly rotate if CIRCLE_RADIUS is set to zero
Circle center is projected forward CIRCLE_RADIUS from current position
and heading
2013-04-14 10:38:01 +09:00
Randy Mackay fc0c451b69 Copter: remove #ifdef checks for Atmega1280 2013-04-05 22:48:10 +09:00
Randy Mackay a9eb626cb8 Copter: update default Rate Yaw P to 0.20 (was 0.25) 2013-04-01 11:49:50 +09:00
Randy Mackay 36834e77b5 Copter: remove support for CLI Slider 2013-03-18 14:07:04 +09:00
Randy Mackay 597a4b912a Copter: fix to allow building HIL_MODE_SENSORS 2013-03-18 13:41:52 +09:00
Randy Mackay d1344e8c39 Copter: remove #define for CROSSTRACK_GAIN
Note: the cross track is still calculated inside the inertial nav based
loiter and wp controls but it's no longer requires a tunable parameter
2013-03-17 16:56:18 +09:00
Randy Mackay 1b6fcad90a Copter: remove tilt compensation parameter
Note: this idea of feed forward tilt compensation is being incorporated
into the inertial nav based loiter and wp controllers but does not
require a separate tunable parameter
2013-03-17 16:53:32 +09:00
Randy Mackay fdcb78ccf7 Copter: leonard's smoother alt-hold transition
Target altitude when entering alt-hold is based on a projection from
current alt and climb rate
2013-03-17 13:24:49 +09:00
Randy Mackay 150046f2b8 Copter: GPS Failsafe implemented
Switches to LAND mode 5 seconds after losing GPS if you're in a flight
mode that requires a GPS
2013-03-16 17:27:46 +09:00
Randy Mackay a73f50494c TradHeli: remove duplicate RC_FAST_SPEED definition 2013-03-04 23:45:23 +09:00
Randy Mackay 33bd984a91 Copter: remove unused input_voltage parameter 2013-03-03 23:23:54 +09:00
Randy Mackay d6ff5ae261 Copter: add roll-pitch slew for auto modes
Added reporting of roll, pitch inputs for ACRO, AUTO
2013-02-24 14:42:04 +09:00
Randy Mackay e297ba7d18 Copter: update default loiter gains for inertial nav 2013-02-24 14:42:00 +09:00
Randy Mackay cbde042ec5 Copter: remove non-inav loiter and wp controllers
lon_speed, lat_speed changed to float
do_takeoff, do_land now set roll-pitch, yaw and nav modes specifically
removed fast_corners functionality (may need to be reimplemented with
new inertial nav controllers)
2013-02-24 14:41:52 +09:00
Randy Mackay 609676e26c Copter: add logging of compass values
Removed rarely used ITERM because we didn't have enough bits in the log
mask
2013-02-24 14:41:48 +09:00
Randy Mackay 67c69a19ee Copter: remove baro-only alt hold
Saves 8 bytes of memory and more importantly simplifies the alt hold
calculations
2013-02-24 14:41:29 +09:00
Randy Mackay fcf102b2cf Copter: inertial nav waypoint controller
#define added to allow compile time selection of traditional or inav
based loiter and wp controllers
2013-02-24 14:41:09 +09:00
Randy Mackay 8e4c9518ea Copter: increase low voltage check to 10.5v
Change requested by Rob Lefebvre and Richie Wilson
2013-02-23 00:36:51 +09:00
Andrew Tridgell 4c7a1a1806 Copter: change PX4 main baud rate back to 115200
we now use USB console
2013-02-22 07:04:23 +11:00
Randy Mackay 06a71af12f Copter: THR_MID used to scale manual throttle 2013-02-01 22:37:16 +09:00
Randy Mackay ce370bab0c Copter: rename CUR and CURR to CURRENT for logging
Based on user complaint that enable/disable was using CUR while message
was appearing as CURR
2013-01-26 17:20:41 +09:00
Randy Mackay b74fe10aa9 Copter: set each flight mode's nav_mode
Allow ACRO flight mode's roll, pitch, yaw, throttle and nav mode to be
overwritten
2013-01-25 15:57:55 +09:00
Andrew Tridgell f303554259 Copter: run serial0 at 57600 on PX4 2013-01-22 09:50:22 +11:00
Robert Lefebvre dde713aaa5 Arducopter: Backing out my changes for a new Loiter Repositioning mode. Leonard and Jonathan's work will trump this. 2013-01-20 21:32:00 +09:00
Andrew Tridgell 580abf1106 Copter: fixed PX4 mag orientation 2013-01-17 17:23:34 +11:00
James Bielman 5631f865b2 Update floating point calculations to use floats instead of doubles.
- Allows use of hardware floating point on the Cortex-M4.
- Added "f" suffix to floating point literals.
- Call floating point versions of stdlib math functions.
2013-01-16 13:52:01 +11:00
Randy Mackay fef7569dee Copter: added experimental LOITER_REPOSITIONING #define to config.h
APM_Config.h should be used to overriding the standard parameters but
they still require a definition in config.h or they will be undefined
when built by the mission planner.
2013-01-14 13:34:14 +09:00
Randy Mackay 9ad6f711f8 ArduCopter: replace FS_THR_RTL_MIN_DISTANCE with wp_radius
This effectively means that an RTL kicked off by a failsafe will
immediately switch to LAND mode only if within 2 meters.  Previously the
radius was much wider (15m).
2013-01-13 20:00:47 +11:00
Randy Mackay 12f885c33c ArduCopter: disable ITERM logging by default
This message takes 1ms to write and we are running over our limits on
some loops.
2013-01-13 20:00:39 +11:00
rmackay9 21b6c78d12 ArduCopter: added get_throttle_althold_with_slew to allow slower altitude target changes
Improved surface tracking by using slewed althold controller
Reduced sonar mode filter to just 3 elements to reduce lag but at the possible consequence of allowing sonar noise to creep through for people with margin sonar set-ups.
2013-01-13 19:51:47 +11:00
Randy Mackay 87627d883b ArduCopter: use new logging method for remaining packet types
Additional changes include renaming RAW dataflash type to IMU
2013-01-13 00:17:44 +09:00
James Bielman 7827a4a54a ArduCopter: Add AP_HAL_SMACCM support.
- Added default configuration to "config.h".
- Added main function to run under FreeRTOS with HWF4.
2013-01-09 11:19:51 -08:00
James Bielman ab37f833db MS5611: Fix CONFIG_MS5611_SERIAL definitions.
- Make sure the values are defined as integers.  We were always using
  SPI rather than using I2C when desired.
2013-01-09 11:19:51 -08:00
Andrew Tridgell c48714be16 Copter: enabled PX4 sensors 2013-01-05 20:39:31 +11:00
James Bielman 264db3670e AP_Baro: Add CONFIG_MS5611_SERIAL option to choose between SPI and I2C.
- Update ArduCopter and ArduPlane modules to pass the correct serial
  driver to the MS5611 driver.
- Update barometer examples, assuming SPI.
2013-01-03 13:48:06 -08:00
Andrew Tridgell 94e3322e24 Copter: fixed build on px4 2013-01-02 22:09:02 +11:00
rmackay9 9b2956b377 ArduCopter: increase throttle rate P to 6.0 (was 1.0) and alt hold P to 2.0 (was 1.0) 2013-01-02 09:55:37 +11:00
rmackay9 d400e5040b ArduCopter: turn on INERTIAL_NAV_Z in the config.h file so that it takes effect when built for the mission planner 2013-01-02 09:55:37 +11:00
rmackay9 e850ab7ccd ArduCopter: add AUTO_VELZ_MIN, AUTO_VELZ_MAX and PILOT_VELZ_MAX to allow better control of climb/descent rate in auto and manual throttle modes 2013-01-02 09:24:31 +11:00
rmackay9 5526ca204c ArduCopter: on throttle failsafe, only initiate RTL if we are at least 15m from home 2013-01-02 09:22:51 +11:00
Robert Lefebvre 6e64b1b357 ACM: Precision Loiter RePositioning code.
Protected behind a #define
2013-01-02 09:19:39 +11:00
rmackay9 e6519330f4 ArduCopter: remove unused rc_override variables to save 21 bytes 2013-01-02 09:19:17 +11:00
rmackay9 34e18ae12a ArduCopter: increase accel based throttle PIDs and add D term to rate based throttle 2013-01-02 09:19:17 +11:00
Robert Lefebvre 9605bd8ee1 ACM: Trying to set a default MPU6K filter rate of 10Hz for TradHeli. Doesn't Work. 2013-01-02 09:14:55 +11:00
rmackay9 d8e3d5c10c ArduCopter: allow RTL's yaw mode to be overridden with a #define in APM_Config.h 2013-01-02 09:12:40 +11:00
rmackay9 50d46898fb ArduCopter: allow GUIDED mode roll-pitch, yaw and throttle control modes to be overridden 2013-01-02 09:12:17 +11:00
Andrew Tridgell 9e986801c9 Copter: fixed SITL for ArduCopter 2012-12-20 14:52:34 +11:00
Pat Hickey 5e63491994 ArduCopter: fix issues with HAL/HIL mixup and baro/compass instances 2012-12-20 14:52:29 +11:00
Pat Hickey d93d932831 ArduCopter: defines fixes
Conflicts:

	libraries/AP_Common/Arduino.mk
2012-12-20 14:52:28 +11:00
Pat Hickey 2aa4657315 ArduCopter: changes to use CONFIG_HIL_BOARD 2012-12-20 14:52:28 +11:00
rmackay9 2f748f8382 ArduCopter: renamed BATT_FAILSAFE to FS_BATT_ENABLE 2012-12-10 23:47:14 +09:00
rmackay9 d31efebd44 ArduCopter: rename throttle failsafe parameters.
Switch to LAND flight mode if throttle failsafe triggers and we do not have a GPS.
THR_FAILSAFE renamed to FS_THR_ENABLE.
THR_FS_VALUE renamed to FS_THR_VALUE.
THR_FS_ACTION removed (action is now controlled by setting FS_THR parameter).
2012-12-10 23:38:43 +09:00
rmackay9 2f1b2b70e6 ArduCopter: added ACRO_TRAINER parameter to allow enabling/disabling the acro training function which will bring the roll back to within +- 45 degrees 2012-12-10 22:27:46 +09:00
rmackay9 dadad8677e ArduCopter: added descriptions for most parameters that did not have them
Renamed loiter_radius to circle_radius to better reflect it's purpose.
Removed some unused parameters including WP_MODE, WP_MUST_INDEX, LOG_LASTFILE, AXIS_P
2012-12-10 21:45:57 +09:00
rmackay9 cfe2507c0b ArduCopter: reduce Rate Roll/Pitch P to 0.150 (was 0.175) and increase I to 0.1 (was 0.01) 2012-12-09 18:08:45 +09:00
Robert Lefebvre aa4d4f8c24 ACM: Adding Pre-Compiler Define for Stabilize Throttle Mode. 2012-12-08 20:41:05 -05:00
Robert Lefebvre 1b97a92098 ACM: Code Cleanup 2012-12-08 14:49:38 -05:00
rmackay9 f98a807d36 ArduCopter: remove debug related to yaw mode used for alt hold 2012-12-08 14:24:50 +09:00
rmackay9 9dd978576b ArduCopter: auto yaw changes to allow pilot override of yaw during missions
Added set_yaw_mode to better control of yaw controller changes and variable initialisation.
Replaced AUTO_YAW mode with separate yaw controllers YAW_LOOK_AT_NEXT_WP, YAW_LOOK_AT_LOCATION, YAW_LOOK_AT_HEADING.
Pilot manual override of yaw causes yaw to change to YAW_HOLD (i.e. manual yaw) until next waypoint is reached.
Added get_yaw_slew function to control how quickly autopilot turns copter
Changed YAW_LOOK_AHEAD to use GPS heading and moved to new get_look_ahead_yaw function in Attitude.pde
Renamed variables: target_bearing->wp_bearing, original_target_bearing->original_wp_bearing.
Removed auto_yaw_tracking and auto_yaw variables and update_auto_yaw function as they are no longer needed.
Simplified MAV_CMD_CONDITION_YAW handling (do_yaw).  We lose ability to control direction of turn and ability to do long panorama shots but it now works between waypoints and save 20bytes.
2012-12-08 14:23:32 +09:00
rmackay9 68ca123224 ArduCopter: remove some unused #defines 2012-12-07 15:17:35 +09:00
rmackay9 3a90fc77f9 ArduCopter: add dataflash logging of camera events 2012-12-07 00:57:08 +09:00
rmackay9 a5bb54e36e ArduCopter: RTL clean-up and slightly improved landing sensor
Consolidated RTL state to be captured by rtl_state variable.
Combined update_RTL_Nav and verify_RTL functions which performed the same function but one was for missions, the other for the RTL flight mode.
Renamed some RTL parameters and global variables to have RTL at the front.
Landing detector now checks accel-throttle's I term and/or a very low throttle value
2012-12-06 10:31:52 +09:00
rmackay9 072ffec493 ArduCopter: allow INERTIAL_NAV to be enabled separately for horizontal and vertical position 2012-12-06 10:31:41 +09:00
rmackay9 bdb47c449a ArduCopter: pass linear altitude error to throttle rate controllers.
Previously the requested rate used the square root of the altitude error.

Scale pilot's desired vertical rate and acceleration based on ACCELERATION_MAX_Z and VELOCITY_MAX_Z #defines
2012-12-06 10:31:31 +09:00
rmackay9 7b4ed2d227 ArduCopter: restored landing detector to landing throttle mode.
Added LAND_SPEED parameter to control the rate of descent for the last 10m of a landing.
Added CH6 tuning for accel based throttle controller.
2012-12-06 10:31:20 +09:00
rmackay9 560bb1d738 ArduCopter: removed unused AUTO_THROTTLE_HOLD #define 2012-12-06 10:31:15 +09:00
rmackay9 3cbef57c64 ArduCopter: first merge of leonard's accel based altitude controller plus other changes from Randy
Changes include:
New low-level get_throttle_accel function takes target acceleration and compares vs earth-frame Z accelerometer values to produce output to motors.
Higher level throttle controllers modified to call new get_throttle_accel controller
Throttle_rate_stabilized controller added which maintains a desired climb/descent rate
Throttle_land controller added - descends using normal auto throttle controller to 10m then descends at 50cm/s
Multiple throttle modes added including landing mode
Land flight mode no longer needs GPS
Throttle cruise maintenance moved to update_throttle_cruise function
2012-12-06 10:30:49 +09:00
Andrew Tridgell 6fbf5ec8f2 Copter: update ArduCopter for new ins interface 2012-11-30 07:15:18 +11:00
Robert Lefebvre 6b8c39dd10 ACM: Creating Yaw_Look_Ahead yaw mode.
This function is not fully tested yet.
2012-11-26 21:37:13 -05:00
Robert Lefebvre 6ffc115236 Changes to get_throttle_rate()
Commented out a bit of code that is not used currently
Change the output constrains to #defines so they can be easily changed, particularly for use in TradHeli.
2012-11-21 17:11:38 -05:00
Andrew Tridgell dafaa2efc8 SITL: disable optical flow on the desktop build
it doesn't work yet, as no sensor emulator is available
2012-11-19 09:04:03 +11:00
rmackay9 07a7a1acd8 ArduCopter: replaced digitalRead and digitalWrite with faster calls
improved performance logging to dataflash
2012-11-19 01:16:07 +09:00
rmackay9 e92b560df5 ArduCopter: low baterry failsafe 2012-11-15 23:35:41 +09:00
Jason Short 9735a0eff1 ACM: Allow for user defined roll and pitch input max 2012-11-11 18:00:10 -08:00
rmackay9 e212744f4c ArduCopter: failsafe improvements
resolves momentary throttle drop to zero before failsafe engages
resolves motor cut after 30seconds if flying in stabilize without GPS (now switches to ALT_HOLD with target altitude zero)
disables motors if throttle was zero before failsafe event
2012-11-11 22:11:12 +09:00
Jason Short 129ec35c35 ACM crosstrack min distance 2012-11-09 22:15:16 -08:00
Jason Short 4d7b9137fe ACM: Added max RTL altitude 2012-11-09 22:15:15 -08:00
rmackay9 1f801714e8 ArduCopter: incorporate new version of inertial navigation
Moved several navigation functions from ArduCopter.pde to navigation.pde
2012-11-07 19:21:31 +09:00
Jason Short 73bc90f9b8 ACM: config.h cleanup
Added LOG_ITERM default to enabled
2012-10-27 09:59:57 -07:00
rmackay9 5e8043fd9c ArduCopter: changed ACRO_ROLL_STABILIZE and ACRO_PITCH_STABILIZE to parameters
Changes on behalf of Leonard Hall
2012-10-23 21:30:50 +09:00
rmackay9 78316adf75 ArduCopter: replace Serial.print with Serial.print_P to save memory.
Includes replacing flight_mode_strings with print_flight_mode function.
SendDebug macro replaced with direct Serial.print_P calls.
2012-10-22 16:45:24 +09:00
Robert Lefebvre bfade7d0ed Fixed that last commit
#define Stupid_Mistake
2012-10-18 16:50:42 -04:00
Robert Lefebvre 592f4040fd Changed RLT Yaw Mode for TradHeli. Also a few comment cleanups. 2012-10-18 16:39:05 -04:00
rmackay9 583f2e49a3 ArduCopter: integrated Leonard Hall's improved ACRO mode 2012-10-18 23:24:34 +09:00
rmackay9 7d7de976c3 ArduCopter: reduced optical flow's I and IMAX terms 2012-10-17 17:47:43 +09:00
LeonardTHall d7b7e1cefa New Yaw controller using rate feed forward and stabilize.
Signed-off-by: LeonardTHall <LeonardTHall@gmail.com>
2012-10-15 11:37:49 +09:00
rmackay9 ee5dab9647 ArduCopter: enable ACRO mode's AXIS_LOCK by default 2012-10-14 19:50:45 +09:00
rmackay9 997fe85880 ArduCopter: fixed acro mode
Changes included:
Removing earth frame roll_rate_trim, pitch_rate_trim and yaw_rate_trim.
Switch ACRO mode to use YAW_ACRO instead of YAW_HOLD.
Changed YAW_ACRO to use stabilize yaw when axis_enabled.
Reset ACRO roll, pitch and yaw targets to current attitude when first entering ACRO.
2012-10-14 17:47:46 +09:00
rmackay9 4a41a3d210 ArduCopter: added BATT_VOLT_PIN and BATT_CURR_PIN parameters to allow support for new 3DR IV battery voltage and current monitor 2012-10-13 18:40:46 +09:00
Robert Lefebvre dae81d2068 Added #define for Tilt_Compensation.
Also added some detail to WP_Speed_Max parameter.
2012-10-12 14:51:31 -04:00
rmackay9 03933df5b7 ArduCopter: set default rate roll and pitch I terms to 0.010, and rate yaw to 0.015
Updated after discussing with Marco
2012-10-11 17:25:01 +09:00
rmackay9 35fa50234f ArduCopter: move I terms from stabilize to rate controllers 2012-10-11 17:20:05 +09:00
rmackay9 af1d6a9b82 ArduCopter: reduce Stabilize Yaw P term to 4.5 2012-10-03 14:19:49 +09:00
rmackay9 ea4f256f8e ArduCopter: BATT_PIN parameter added to allow you to select which pin is used for voltage and current measurements
To save a parameter, the current sensor pin is assumed to always be 1 higher than the voltage pin.
2012-10-02 22:16:19 +09:00
rmackay9 95763e610b ArduCopter: allow DMP to run in parallel with DCM
Parallel DMP can be enabled by #define SECONDARY_DMP_ENABLED in APM_Config.h
New DMP dataflash log type added to allow easy comparison with DCM
2012-09-30 00:25:40 +09:00
rmackay9 41fbb19cf5 AP_InertialSensor_MPU6000: replaced _cs_pin parameter with #define and saved 1 byte of memory
Updated ArduCopter, ArduPlane and example sketches in AP_InertialSensor, AP_IMU and AP_AHRS libraries because they no longer need to pass in cs_pin to the constructor
2012-09-28 19:21:59 +09:00
rmackay9 fff5d51694 ArduCopter: reduced Loiter Rate I to 0.04 (was 0.08) 2012-09-25 19:08:31 +09:00
rmackay9 a71aa21514 ArduCopter: increase default Loiter Rate P to 5.0 2012-09-25 12:19:44 +09:00
rmackay9 9e66b555cb ArduCopter: removed INSTANT_PWM from ArduCopter and AP_Motors library 2012-09-13 21:31:13 +09:00
rmackay9 42406c827a ArduCopter: added NUM_IMU_SAMPLES_FOR_XYZHZ definitions for MPU6000 and Oilpan to allow more syncing of the mainloop with the arrival of data from the IMU. 2012-09-10 11:37:48 +09:00
Craig Elder 274b2e2143 Arducopter: Release 2.7.2 2012-08-31 19:18:10 -07:00
Andrew Tridgell e8d928cca4 ACM: added TELEM_DELAY to ArduCopter 2012-08-30 09:03:01 +10:00
Craig Elder 4ad516c445 Arducopter: increased MAVLINK delay to 6s to reduce the chance of xBee bricking
Arduplane:  increased MAVLINK delay to 6s to reduce the chance of xBee bricking
Ardurover:  increased MAVLINK delay to 6s to reduce the chance of xBee bricking
2012-08-28 20:09:10 -07:00
rmackay9 2ad6dcb7c4 ArduCopter: increased Stabilize Roll and Pitch I term to 0.05 (was 0.01) based on feedback from Jason 2012-08-29 11:34:53 +09:00
rmackay9 b4b394e67e ArduCopter: reduced Rate Roll and Pitch PID values
RATE_ROLL_P, RATE_PITCH_P reduced to 0.165 (was 0.185)
RATE_ROLL_D, RATE_PITCH_D reduced to 0.004 (was 0.008)
2012-08-26 10:45:45 +09:00
uncrustify 429c41155c uncrustify ArduCopter/config.h 2012-08-21 19:19:50 -07:00
Andrew Tridgell 6d11940ada AHRS: removed Quaternion build support from APM/ACM/rover 2012-08-22 10:42:21 +10:00
rmackay9 1d32e03f61 ArduCopter: added ACCEL_ALT_HOLD and INERTIAL_NAV to config.h and commented out of APM_Config.h.
Reduces possibility of difference between arduino ide compiled code and script built code (i.e. autotester, mission planner)
2012-08-19 12:31:02 +09:00
Jason Short 3ee2fd3fb6 ACM: Config.h - added default for toy mixer 2012-08-16 15:40:28 -07:00
Jason Short 9a568385b0 ACM increase the minimum speed at WP 2012-08-10 10:01:40 -07:00
Jason Short 3e57f8afd8 ACM: config.h = updated default gains
More yaw rate control
2012-08-09 16:59:43 -07:00
Amilcar Lucas d34549f386 Add an optional second mount to ArduPlane and ArduCopter 2012-08-08 23:22:24 +02:00
Amilcar Lucas 9cc705939a Add a second mount instance 2012-08-08 23:07:25 +02:00
Amilcar Lucas aa3cc63b15 ArduCopter: Make the code fit in a 1280 chip again
Even allows to control a camera/antenna mount, if the user explicitly wants to.
2012-08-06 00:23:48 +02:00
Amilcar Lucas 0106c133cf Default CLI_SLIDER_ENABLED to DISABLED
Chris asked for this on the mailing list
2012-08-06 00:22:33 +02:00
Amilcar Lucas afd96025a7 ArduCopter: Save more space in APM1280 2012-08-05 23:05:52 +02:00
Amilcar Lucas d29f7023cc Merge from ArduPlane 2012-08-04 18:38:50 +02:00
rmackay9 77b1785bc6 ArduCopter: reduce stabilize roll, pitch and rate yaw IMAX values 2012-07-30 11:01:45 +09:00
rmackay9 014f5aae99 ArduCopter: added DMP_ENABLE #define and CH6 tuning value for AHRS_KP 2012-07-28 14:21:07 +09:00
Jason Short 96aabb7712 ACM: Lowered default Alt hold P 2012-07-21 16:45:00 -07:00
Jason Short 3b496ff229 Arducopter: Upped D rate to .005 by default 2012-07-19 22:35:21 -07:00
Jason Short 49c7579079 Arducopter: Config.h defaults adjustments 2012-07-19 17:48:48 -07:00
Jason Short 3401bd3583 Arducopter: Clarified units in comment 2012-07-19 09:49:13 -07:00
Jason Short dcf9f9dab1 Arducopter
for rate altitude changes
2012-07-18 22:57:10 -07:00
Andreas M. Antonopoulos a976a59c88 AP_Limits: Configuration defaults moved to config.h. Fixed AP_LIMITS==DISABLED handling. 2012-07-16 11:46:43 -07:00
rmackay9 36ecdff593 ArduCopter: removed unused config for CAM_ROLL_GAIN and CAM_ROLL_PITCH now in AP_Mount library) 2012-07-15 16:38:52 +09:00
Jason Short 7a5544051d Arducopter
Lowered WP speed default to 500. 600 was quite high once the nav routines were fixed and quad could achieve that speed.
2012-07-11 17:46:07 -07:00
Jason Short c04bff67de Arducopter: Config.h, default gain tweaks from flight tests. 2012-07-10 21:53:38 -07:00
Amilcar Lucas dfe0983e1e Merge the changes from APM_Camera branch into ArduCopter
Conflicts:

	ArduCopter/Camera.pde
	ArduCopter/Parameters.pde
2012-07-11 00:39:13 +02:00
Jason Short 038116f521 Airspeed patch:
pre-calculated airspeed resistance pitches copter automatically to gain a certain speed allowing the speed controller to work off of a better set point - similar to Alt hold.
added param tilt_comp with a default of 54 which equals 19.5° of pitch to go 6m/s
upped Z and Y target speeds to int32_t for speed squared calculation
2012-07-09 13:13:32 -07:00
Andrew Tridgell 60caaa4b04 MAVLink: remove MAVLink 0.9 protocol support
this simplifies the code a lot. We're not going back to 1.0
2012-07-05 13:00:46 +10:00
Adam M Rivera 6e93ab6af6 Parameters: Added flag for camera pitch/roll servos (continuous or regular) 2012-07-04 21:06:21 -05:00
Jason Short 37685756df Config.h:
decreased alt hold_P to .4
removed RTL_AUTO_LAND default
increased alt hold I
2012-07-03 17:37:37 -07:00
Jason Short 2d572461ec Config: increased WP distance to 2m but default, removed alt hold D: causing issues with APM1 noise. 2012-07-03 17:18:33 -07:00
Jason Short 8a08a74cc6 Config.h : shortening the landing time to 10s 2012-07-02 17:52:38 -07:00
Jason Short 8ab1acfb92 Config.h
Removed Approach delay redundancy - using land timer instead
Removed Retro loiter mode param
2012-07-01 13:40:11 -07:00
rmackay9 78fa903e17 ArduCopter: updated STABILIZE_ROLL_I to 0.01 (was 0.1) as instructed by Marco 2012-06-30 19:26:14 +09:00
Jason Short 4450d80ea3 Config.h: Optimizing Nav gains 2012-06-29 21:20:28 -07:00
Jason Short c76ac4543b Added user editable define for Super simple radius 2012-06-26 10:38:46 -07:00
Jason Short a0dc1f7ab1 Config.h : New Gains based on testing, new Crosstrack gain. from 1.0 to .2 because of new algorithm 2012-06-25 23:06:28 -07:00
Jason Short 7e0708ca36 Config.h - returned low to original 120 2012-06-20 15:22:35 -07:00
Jason Short 4f18e7f80b lowered minimum throttle 2012-06-20 08:47:47 -07:00
Jason Short 39a253a273 decreased I term based on the tests last weekend in high winds 2012-06-20 08:47:47 -07:00
rmackay9 65050775e1 ArduCopter: made Robert's new yaw method optional (off by default).
Add this line to APM_Config.h to enable Robert's yaw
#define ALTERNATIVE_YAW_MODE ENABLED
2012-06-13 21:50:16 +09:00
Jason Short ff0659535e Raised the Max throttle to 1000, min to 200. Worked good in SIM with Tridge's motor safety patch. 2012-06-12 13:58:49 -07:00
rmackay9 c6f1d93849 ArduCopter: updated standard loiter pids.
Loiter_P (speed from distance to target) = 0.2 (was 0.35)
Loiter_Rate_P (lean angle from desired acceleration) = 2.4 (was 2.5)
Loiter_Rate_I = unchanged at 0.08
Loiter_Rate_D = 0.40 (was 0.45)
2012-06-12 20:56:31 +09:00
Jason Short a9610a0761 Stabilization patches
removed Angle error limit for stabilization
constricted Iterm to +- 5° error and limited the implementation to when the quad is +- 5° from center
doubled the output limit for Rate controller.
increased default Rate_P gain to .18 with matching Rate_D of .004
Tested in the SIM and in backyard. dramatically increases performance and quad no longer overshoots and flips when pushed hard.
2012-06-05 16:41:44 -07:00
Michael Oborne a71ed6c5ce enable mavlink10 by default 2012-06-04 08:02:08 +08:00
Jason Short 9310d613e1 Lowered I term - causes oscillations in SIM 2012-05-29 12:43:01 -07:00
Jason Short 7f3e142fa8 Loiter Gains based on new SIM 2012-05-15 22:01:01 -07:00
Robert Lefebvre c8fb9a6635 More CopterLEDS changes.
Merged CopterLEDS and Piezo functions to eliminate pin conflict on APM2.  Created new Parameter bit to turn piezo function on and off from MP. Moved GPS and Aux pin assignments to allow commonality between APM1 and 2.  Set LED_Mode parameter default to 9 in order to make CopterLEDS completely backwards compatible with old Motor LEDS and Piezo code.  Legacy users should see no difference.
2012-05-15 12:00:21 -04:00
Robert Lefebvre a285e2779f CopterLEDS changes for APM2 2012-05-15 10:07:03 -04:00
Adam M Rivera 8e580729b7 config.h: Removed comment. 2012-04-23 00:16:41 -05:00
Adam M Rivera 97040a7b3a Merge branch 'master' of https://code.google.com/p/ardupilot-mega into auto-approach 2012-04-23 00:03:37 -05:00
rmackay9 090f5aaa6f ArduCopter - config.h - set standard RC_SPEED to 125 for helicopter frame 2012-04-21 23:46:36 +09:00
rmackay9 919f004b27 ArduCopter - changed Optical Flow for APM2 to use A3 pin 2012-04-21 20:15:16 +09:00
Adam M Rivera c233defbe6 Merge branch 'retro-loiter' of https://code.google.com/r/a432511-wip into auto-approach
Conflicts:
	Tools/ArdupilotMegaPlanner/Common.cs
2012-04-19 11:08:34 -05:00
Adam M Rivera 24363ccb83 Merge branch 'master' of https://code.google.com/p/ardupilot-mega into retro-loiter 2012-04-19 10:17:36 -05:00
Adam M Rivera d29f1ef331 Loiter: Made the "retro loiter" routines configurable. Add RETRO_LOITER_MODE ENABLED to APM_Config.h to enable the older loiter shtuff. 2012-04-19 10:16:29 -05:00
James Goppert 0e7e77760a Updated ArduPlane/ArduCopter cmake options. 2012-04-18 15:16:02 -04:00
Adam M Rivera 7b277d7044 config.h: Added RTL_APPROACH_DELAY config value. 2012-04-16 14:00:08 -05:00
rmackay9 84b07b5e6a ArduCopter - LEDS - added new COPTER_LEDS definition
Code by Robert Lefebvre
2012-04-12 22:55:32 +09:00
Andrew Tridgell 0bc604f030 ACM: removed FORCE_AUTOMATIC_DECLINATION_UPDATE
we now have the EEPROM option COMPASS_AUTODEC instead
2012-03-30 14:25:27 +11:00
Adam M Rivera 51b70e4d36 ArduCopter: Changed implementation of configuration value for automatic declination. There is now a FORCE_AUTOMATIC_DECLINATION_UPDATE that when enabled will update the declination on every GPS 3D fix regardless of whether or not the user saved a value to the EEPROM. By default the declination will only be set by the automatic declination routine if the user has not saved a declination to the EEPROM. 2012-03-30 14:25:06 +11:00
rmackay9 1f4cfb9333 ArduCopter - added PID log type. Implemented for Yaw stabilize and rate controllers. 2012-03-25 16:09:08 +09:00
Jason Short e2560c5865 Throttle_hold was in APM_Config - which is ignored by the Mission planner Hex generator 2012-03-22 10:01:24 -07:00
rmackay9 0773a25b5d ArduCopter - increased default THROTTLE_CRUISE to 450 2012-03-20 16:34:07 +09:00
rmackay9 dc92da818c ArduCopter - remove reference to AUTO_RESET_LOITER that is not used anymore 2012-03-18 14:53:19 +09:00
Jason Short 491af02d8a ACM: Lowered gains from flight tests today with 3DR Quad 2012-03-17 11:04:01 -07:00
Jason Short 3038da1dc3 ACM: Softer Loiter Gains 2012-03-16 14:10:19 -07:00
Jason Short a52a14bf12 Tune down Loiter_P a hair 2012-03-15 19:17:27 -07:00
Jason Short 48ba24a810 ACM: Loiter tuning updates, turned up I a bit, a higher I will work better if the system is well tuned. 2012-03-13 10:23:31 -07:00
Jason Short 7034b709d1 ACM: removing old define 2012-03-12 13:11:30 -07:00
Jason Short 0b51d9b8b0 ACM: Made Loiter_D 0 by default. Accidentally left it on by default. 2012-03-12 10:37:15 -07:00
Jason Short a989b88680 ACM: made same as Loiter I 2012-03-11 23:21:49 -07:00
Jason Short 0d434ca92c ACM: Tuning based on flights today 2012-03-11 23:21:49 -07:00
Adam M Rivera 2524f9c8df AP_Declination: Added new config value to allow the user to have the declination overwritten on every 3D fix.
Signed-off-by: Andrew Tridgell <tridge@samba.org>
2012-03-11 20:59:47 +11:00
Jason Short 83729d0f75 ACM: decreased rate P for alt hold to remove bumpy repsonse 2012-03-10 12:41:06 -08:00
Jason Short 220d5a1c6e ACM: Increased the altitude error P for smoother alt hold response 2012-03-10 12:40:44 -08:00
Jason Short 4b703e8842 decreased the loiter rate P for overshoot 2012-03-10 12:40:07 -08:00
Andrew Tridgell 7e4c8592ff ACM: make it possible to build ArduCopter with quaternions 2012-03-10 10:34:29 +11:00
Jason Short 730476fdfd ACM -
Implemented automatic ranging of Alt Hold gains. Works well in simulator and testing.
- alt hold estimation moved to 50 hz
- simple fixed observer calc for smooth and accurate climb rates useful for derivative calcs
- auto-reset of the I term by moving I value into throttle value. This recalcs the gain every 20seconds for battery drainage compensation in long flights.
- remove filtering for Nav_throttle
- added a way to lower the gain on nav_throttle for descents by / climb_rate error by 2 - seems to work OK and keeps copter from dropping like a rock when the Baro drifts quickly lower.
- removed old throttle hold set point code
- made throttle override for alt hold +- 200 vs 250
2012-03-06 22:22:14 -08:00
Jason Short c26eb6afcc ACM: Updated config values 2012-03-06 22:12:24 -08:00