Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
254 commits
Select commit Hold shift + click to select a range
c395a66
DataFlash: moved UBX logging headers to DataFlash
Aug 17, 2014
57956db
AP_GPS: moved UBX log headers to DataFlash
Aug 17, 2014
ecd7341
Copter: set GPS non-blocking
Aug 18, 2014
54af047
HAL_PX4: prevent read past end of buffer
Aug 18, 2014
308c90f
HAL_VRBrain: prevent read past end of buffer
Aug 18, 2014
9c79f9b
Copter: add ACRO_EXPO param values
rmackay9 Aug 19, 2014
2d02d8d
Copter: remove inav check
rmackay9 Aug 20, 2014
deaffec
AC_AttitudeControl_Heli: Create Flybar Passthrough flag which will be…
R-Lefebvre Jul 3, 2014
ede4b56
TradHeli: Add pointer for pilot roll/pitch inputs to attitude_control…
R-Lefebvre Jul 3, 2014
244d381
AC_AttitudeControl_Heli: Add passthrough_to_motor_roll_pitch function.
R-Lefebvre Jul 3, 2014
9326d36
AC_AttitudeControl_Heli: Add use_flybar_passthrough accessor function.
R-Lefebvre Jul 3, 2014
184be13
TradHeli: Set Flybar passthrough mode in Acro Initialization function.
R-Lefebvre Jul 3, 2014
1becab3
TradHeli: Reset flybar passthrough to false when exiting Acro mode.
R-Lefebvre Jul 3, 2014
32cb2bb
TradHeli: Add yaw-only rate request function for flybar acro mode.
R-Lefebvre Jul 4, 2014
8ac3689
Logging: Fix comment error.
R-Lefebvre Jul 9, 2014
440f4eb
AC_AttControlHeli: add passthrough_bf_roll_pitch_rate_yaw
rmackay9 Aug 20, 2014
c7d6b02
TradHeli: call passthrough_bf_roll_pitch_rate_yaw
rmackay9 Aug 20, 2014
06880f5
TradHeli: update AttControlHeli constructor
rmackay9 Aug 20, 2014
f448320
Rover: show firmware version on param list
Aug 22, 2014
f86de61
Copter: show firmware version on param fetch
Aug 22, 2014
91817b0
AC_AttControl: div-by-zero check for bf-to-ef conversion
rmackay9 Aug 22, 2014
06e0643
AC_AttControlHeli: integrate div-by-zero check for bf-to-ef conversion
rmackay9 Aug 22, 2014
d242fca
Copter: remove get_angle_targets_for_reporting fn
rmackay9 Aug 22, 2014
d7d90b4
AC_AttControl: remove debug message
rmackay9 Aug 22, 2014
ec2308b
AC_AttControl: bug fix for ef target during acro
rmackay9 Aug 23, 2014
6a654ff
AP_NavEKF: make use_compass() public
Aug 24, 2014
62d526a
AP_AHRS: use EKF use_compass() if EKF enabled
Aug 24, 2014
f78aff6
Copter: make landing detector more strict
rmackay9 Aug 25, 2014
4038cd2
Copter: remote arming check reference to compass learning
rmackay9 Aug 26, 2014
7802c85
Copter: pre-arm check of internal vs ext compass
rmackay9 Aug 26, 2014
5759a69
Mission: start next nav cmd immediately after prev completes
rmackay9 Aug 27, 2014
ff94120
AC_WPNav: resolve twitch when passing spline waypoints
rmackay9 Aug 27, 2014
68df421
Copter: throttle deadzone parameter
rmackay9 Oct 27, 2013
515c0d8
Copter: restore CLI set parameter feature
jason4short Aug 29, 2014
15508c4
Copter: default LAND_REPOSITION to 1
rmackay9 Aug 31, 2014
5d7a272
AP_HAL_VRBRAIN: added management for external relay 1 and 2
emilecastelnuovo Aug 21, 2014
781f15b
AP_relay: added default relay pin for VRBRAIN
emilecastelnuovo Aug 21, 2014
f6fada2
VRBRAIN: added startup of internal mag's driver for VR Brain Standard 5
LukeMike Aug 19, 2014
ada7be6
AP_HAL: VRBRAIN corrected EEPROM size and added terrain folder on Mic…
emilecastelnuovo Aug 22, 2014
e995641
AP_HAL_VRBRAIN: enable 2nd GPS for VRBRAIN 5
emilecastelnuovo Aug 22, 2014
4fa8f82
Build: VRBRAIN corrected order of MAG startup
emilecastelnuovo Aug 24, 2014
938f6f2
Build: VRBRAIN corrected order of MAG startup for 4.5 board
emilecastelnuovo Aug 24, 2014
be2dabe
Copter: AC3.2-rc6 release notes
rmackay9 Aug 31, 2014
acecc78
Copter: version to AC3.2-rc6
rmackay9 Aug 31, 2014
7236d06
Copter: update AC3.2-rc6 release notes
rmackay9 Aug 31, 2014
162d421
Copter: update AC3.2-rc6 release notes
rmackay9 Aug 31, 2014
0f2083a
AP_HAL: added missing CONFIG_HAL_BOARD_SUBTYPE #define for HAL_BOARD_…
emilecastelnuovo Aug 14, 2014
1ee6481
Copter: sanity check throttle deadzone
rmackay9 Sep 2, 2014
5ead809
InertialSensor: reorder .cpp file to match .h
rmackay9 Sep 1, 2014
7fc5d69
INS: add get_accel_health_all and get_gyro_health_all
rmackay9 Sep 1, 2014
6c0b9a2
Copter: check all gyros and accels in pre-arm check
rmackay9 Sep 1, 2014
8b91900
Copter: individual accel and gyro status to GCS
rmackay9 Sep 1, 2014
8e7b93d
Copter: pre-arm consistency check of accels
rmackay9 Sep 3, 2014
b214b8b
Copter: add short delay to arming to allow RC input
rmackay9 Sep 4, 2014
dbb0283
Copter: land check gets overall throttle and rotation rate check
rmackay9 Sep 3, 2014
cdc4038
Copter: pre-arm consistency check of gyros
rmackay9 Sep 3, 2014
fe07df5
Cotper: AC3.2-rc7 release notes
rmackay9 Sep 4, 2014
faf1247
Copter: version to AC3.2-rc7
rmackay9 Sep 4, 2014
62a4e66
Copter: increase EKF_CHECK_THRESH default to 0.8
rmackay9 Sep 9, 2014
4b47a61
Copter: reduce alt hold defaults
rmackay9 Sep 7, 2014
0aab3a0
TradHeli: update AttControl params to match multicopters
rmackay9 Sep 9, 2014
c8e6524
DataFlash: allow use of a smaller writebuf for PX4v1
Sep 9, 2014
e706c24
Copter: send extended status to GCS only after initialisation
rmackay9 Sep 9, 2014
cac10a3
Copter: never send unhealthy terrain status
rmackay9 Sep 9, 2014
01536e0
AP_NavEKF : Clean up time stamps
priseborough Sep 5, 2014
058fb8f
AP_NavEKF : Reduce ripple in estimates that can cause copter motor 'p…
priseborough Aug 24, 2014
1ed11c7
Copter: AC3.2-rc8 release notes
rmackay9 Sep 11, 2014
12f3e96
Copter: version to AC3.2-rc8
rmackay9 Sep 11, 2014
d241592
HAL_PX4: fixed dirty_mask calculation in FRAM storage
Sep 11, 2014
939df78
HAL_VRBRAIN: fixed storage bug in VRBRAIN too
Sep 11, 2014
a7233c4
Copter: AC3.2-rc9 release notes
rmackay9 Sep 11, 2014
75a1e46
Copter: version to AC3.2-rc9
rmackay9 Sep 11, 2014
64cc498
Copter: THR_ACCEL_IMAX param range increased
rmackay9 Sep 12, 2014
5fd39ce
Copter: reduce throttle to min once landed in RTL
rmackay9 Sep 12, 2014
0a3ec84
Copter: THR_ACCEL_IMAX default to 800
rmackay9 Sep 12, 2014
b212c02
Copter: version to AC3.2-Iris
rmackay9 Sep 12, 2014
3993927
Copter: Log NTUN while in LAND mode with GPS
jschall Sep 16, 2014
bf1ccba
AP_NavEKF : Reduce sensitivity on filter divergence check
priseborough Sep 15, 2014
be2f308
Copter: reset battery_fs after dis/rearming
AndKe Sep 17, 2014
b8c74b7
Copter: define limit for baro vs inav alt disparity
rmackay9 Sep 18, 2014
a1ea434
Copter: typo fix for baro vs inav alt disparity definition
rmackay9 Sep 18, 2014
ab4b545
AC_WPNav: add loiter_soften_for_landing method
rmackay9 Sep 19, 2014
7f97093
Copter: soften loiter target when maybe landed
rmackay9 Aug 29, 2014
5f909f1
Copter: add land_complete_maybe flag
rmackay9 Sep 19, 2014
93dbfd0
Copter: rename land_maybe_complete function
rmackay9 Sep 19, 2014
1cf7f7e
Copter: increase Alt Disparity check to 2m
rmackay9 Sep 20, 2014
9693ee0
LowPassFilter: add div by zero check
rmackay9 Sep 21, 2014
e047093
AC_PosControl: 2hz filter on accel error
rmackay9 Sep 21, 2014
5e19740
AC_PosControl: 4hz filter on z-axis velocity error
rmackay9 Sep 21, 2014
d66ffd5
Copter: use disparity threshold define for pre-arm checks
rmackay9 Sep 23, 2014
9c3379f
Compass: always default devid to zero
rmackay9 Sep 23, 2014
62339c2
AP_AHRS : Prevent EKF starting if GPS sats less than AHRS_GPS_MINSATS
priseborough Sep 23, 2014
3233416
AP_NavEKF : Reduce weighting on GPS when not enough satellites
priseborough Sep 23, 2014
a0cb430
Copter: allow passthru for ch 9 ~ 14
rmackay9 Sep 23, 2014
9c1b4e2
AP_NavEKF : Explicitly initialise gpsNoiseScaler to default value
priseborough Sep 24, 2014
5624217
Copter: update AC3.2-rc10 release notes
rmackay9 Sep 24, 2014
eb89b53
Copter: version to AC3.2-rc10
rmackay9 Sep 24, 2014
20d35b4
Copter: bugfix to condition-yaw for relative angles
rmackay9 Sep 26, 2014
1f16702
AP_NavEKF : Fix bug in reset of position, height and velocity states
priseborough Sep 16, 2014
a6cd04c
AP_NavEKF : Fix bug in GPS innovation variance growth calculation
priseborough Sep 6, 2014
2d7f819
AC_WPNav: add shift_wp_origin_to_current_pos for takeoff
rmackay9 Sep 29, 2014
da2a463
Copter: shift pos targets to current location before takeoff
rmackay9 Sep 29, 2014
c338b16
GPS: fix SIRF set-binary message
rmackay9 Oct 1, 2014
468ebd8
AP_NavEKF: simplify variable handling in EKF
Oct 1, 2014
89755c2
AP_NavEKF: make it clear that all sat counts are covered
Oct 1, 2014
b51d01f
AP_AHRS : add method to report if EKF is waiting to start
priseborough Sep 29, 2014
29c704f
AHRS: rename ekfNotStarted method to initialised
rmackay9 Oct 2, 2014
3b0a308
Copter: only report ahrs unhealthy after initialisation
rmackay9 Oct 2, 2014
400dd94
TradHeli: remove overall throttle level from landing check
rmackay9 Sep 23, 2014
6cbb9d6
AP_NavEKF : Fix bug in reset of GPS glitch offset
priseborough Oct 2, 2014
e836832
Copter: increase autotune limits
lthall Sep 22, 2014
55173cc
Tri: _min_throttle interpreted as 0~1000 range for throttle_lower flag
rmackay9 Oct 4, 2014
51de79c
MotorsMatrix: _min_throttle interpreted as 0 ~ 1000 range for throttl…
rmackay9 Oct 4, 2014
95b2b45
Copter: ReleaseNotes for AC3.2-rc11
rmackay9 Oct 6, 2014
26b5321
Copter: version to AC3.2-rc11
rmackay9 Oct 6, 2014
a1e707b
Copter: cleanup enabling of cli and frsky telem for APM
rmackay9 Sep 20, 2014
5891cd3
Copter: disable sonar on APM1 and TradHeli on APM2
rmackay9 Oct 7, 2014
a95b8f1
Copter: Rate Pitch IMAX default to 1000
rmackay9 Oct 7, 2014
d309ecb
INS: add gyro_calibrated_ok_all method
rmackay9 Oct 8, 2014
eb59477
Copter: pre-arm check that gyro cal succeeded
rmackay9 Oct 8, 2014
661755e
Copter: report gyro unhealthy if failed calibration
rmackay9 Oct 8, 2014
7f8a68d
Copter: support pre-flight calibration of gyro
rmackay9 Oct 8, 2014
811e857
AP_InertialNav: fixed use of _ahrs.get_relative_position_NED() with E…
Oct 9, 2014
31c256b
AP_InertialNav: fixed use of ahrs.get_velocity with EKF disabled
rmackay9 Oct 9, 2014
01a4ad2
Copter: AC3.2-rc12 release notes
rmackay9 Oct 9, 2014
74e86a3
Copter: version to AC3.2-rc12
rmackay9 Oct 9, 2014
6537432
Copter: auto-trim start delays auto-disarm by 15sec
rmackay9 Oct 9, 2014
4f427c6
AC_PosControl: Protect from divide-by-zero in get_stopping_point_xy
jschall Oct 10, 2014
71722d2
Copter: remove DRIFT and SPORT from manual_flight_mode function
jschall Oct 10, 2014
0dcf501
AP_AHRS: fixed calls to DCM in parent class
Oct 14, 2014
f61ae9e
AP_AHRS: restore DCM attitude before update()
Oct 15, 2014
ed30c09
AP_AHRS: use a common function for updating the CD values
Oct 15, 2014
470fcc2
Copter: add DCM_CHECK_THRESH parameter
rmackay9 Oct 16, 2014
7e1c975
Copter: add DCM check of yaw error
rmackay9 Oct 16, 2014
c093160
Copter: support logging while disarmed
Oct 17, 2014
d58f7ad
Copter: remove extra in_mavlink_delay from should_log function
rmackay9 Oct 17, 2014
92225dc
Copter: add NearlyAll-AC315 LOG_BITMASK description
rmackay9 Oct 17, 2014
820b4e2
AP_Compass: added set_offsets() interface
Oct 14, 2014
bbb6471
Replay: fixed loading of users parameters and parameter override
Oct 14, 2014
cd35293
Parachute: set servo or relay to off position on every update
rmackay9 Oct 18, 2014
9d76d3b
Copter: log DCM reported roll-pitch and yaw error
rmackay9 Oct 18, 2014
d71b08a
AP_Motors: reduce slow-start increment for fast CPUs
rmackay9 Oct 18, 2014
8da15cb
Copter: check target of set-mode request from GCS
rmackay9 Sep 27, 2014
d37c788
AP_NavEKF: Track baro alt when pre-armed
priseborough Oct 12, 2014
3638bfb
AC_PosControl: bug fix dt calculation
rmackay9 Oct 21, 2014
65472ea
AHRS_DCM: sanity check AHRS_RP_P and AHRS_YAW_P
rmackay9 Oct 21, 2014
ba5e368
AC_WPNav: bug fix sanity check of set_speed_xy
rmackay9 Oct 21, 2014
0335138
Copter: print frame type in log headers
jschall Sep 27, 2014
0d2954b
Copter: landing detector checks baro climb rate
rmackay9 Oct 22, 2014
5cbcbf9
DataFlash: log baro climbrate
rmackay9 Oct 22, 2014
43c5a70
Copter: completely disable vel controller
rmackay9 Oct 23, 2014
00f9882
Copter: remove DO_MOUNT_CONFIGURE support
rmackay9 Oct 23, 2014
a4da667
Mount: remove CMD_DO_MOUNT_CONFIGURE support
rmackay9 Oct 23, 2014
8b87a40
Copter: remove debug
rmackay9 Oct 23, 2014
fdf6aa5
Copter: shorten ESC calibration message
rmackay9 Oct 23, 2014
47418b7
Relay: reduce num relays to 2
rmackay9 Oct 23, 2014
bafd9fd
RangeFinder: reduce num instances to 1
rmackay9 Oct 23, 2014
4bd3f59
Copter: ReleaseNotes for AC3.2-rc13
rmackay9 Oct 23, 2014
83a5102
Copter: version to AC3.2-rc13
rmackay9 Oct 23, 2014
7ad0b61
AP_RangeFinder: auto-update PX4 ll40ls max/min distance
Oct 13, 2014
8041613
RangeFinder: PulsedLight I2C addr to 0x62
rmackay9 Oct 24, 2014
3a8d4cd
Copter: fix to dcm-check to be continuous
rmackay9 Oct 27, 2014
fae45b2
AP_InertialSensor: fixed timer bug in HIL sensors
Aug 19, 2014
1921e22
Copter: ReleaseNotes for AC3.2-rc14
rmackay9 Oct 27, 2014
a9e6c06
Copter: update version to AC3.2-rc14
rmackay9 Oct 27, 2014
ef0b934
Copter: don't stop logging on disarm when LOG_WHEN_DISARMED is set
jschall Oct 22, 2014
95538d2
AHRS: add reset_gyro_drift method
rmackay9 Oct 28, 2014
7b4cd9e
Copter: reset ahrs gyro drift after gyro calibration
rmackay9 Oct 28, 2014
a8a6368
GPS: use primary for Notification
benoit-pereira-da-silva Sep 21, 2014
1ab5d71
GPS: init primary_instance to zero
rmackay9 Oct 29, 2014
d04a740
AP_AHRS : Add reset of EKF gyro bias states
priseborough Oct 29, 2014
a7caa91
AP_NavEKF : Add public method to reset gyro bias states
priseborough Oct 29, 2014
dc3509e
Copter: fail to arm if gyro cal fails
rmackay9 Oct 29, 2014
683f3a5
Copter: re-enable CPU failsafe if arming fails
rmackay9 Oct 29, 2014
ddb8796
Copter: return false when arming fails
rmackay9 Oct 29, 2014
fecad46
AP_NavEKF : add INIT_GYRO_BIAS_UNCERTAINTY definition
priseborough Oct 29, 2014
3a292db
Copter: update AC3.2-rc14 ReleaseNotes
rmackay9 Oct 29, 2014
bd69290
Copter: minor update to AC3.2-rc14 ReleaseNotes
rmackay9 Oct 31, 2014
f8de0ec
Copter: update AC3.2 ReleaseNotes
rmackay9 Nov 7, 2014
c8e0f3e
Copter: update version to AC3.2
rmackay9 Nov 7, 2014
0a3ef32
VRBRAIN: modified target clean
LukeMike Jul 29, 2014
2de18f8
AP_Compass: VRBRAIN. Deal with external mag connected on internal I2C…
emilecastelnuovo Aug 14, 2014
1455d70
VRBRAIN: defined AirSpeed inputs for ArduPlane on VR Micro Brain 5
LukeMike Sep 11, 2014
12ade1e
VRBRAIN: added flag for to build versions with different kind of RC I…
LukeMike Sep 11, 2014
f50d48f
VRBRAIN: added new board VR Brain 5 PRO
LukeMike Sep 12, 2014
45e3b0e
VRBRAIN: added script for build all VirtualRobotix binaries
LukeMike Sep 12, 2014
412de3c
AP_Compass: VRBRAIN add #if !defined() for VRBRAIN 4.5 boards.
emilecastelnuovo Nov 10, 2014
d510819
HAL_PX4: FRAM does not support fsync
tridge Dec 9, 2014
60ded48
DataFlash: don't write out parameters if log open fails
tridge Dec 21, 2014
0c371f1
DataFlash: don't try and open logfile on failure more than once
tridge Dec 21, 2014
506c766
Copter: add throttle_zero state
jschall Oct 7, 2014
8d63a65
Copter: Change all zero throttle checks that should be conservative t…
jschall Oct 7, 2014
9ced648
Copter: throttle zero debounce to separate function
rmackay9 Oct 8, 2014
f64f155
Copter: add land_complete to fence disarm check
jschall Oct 10, 2014
9fc62b5
Copter: use ap.throttle_zero instead of rc_3.control_in in auto_disar…
jschall Oct 10, 2014
7ea5e69
Copter: auto-disarm if land complete regardless of mode
jschall Oct 10, 2014
e05f8d3
Copter: add mode_allows_arming function
jschall Oct 10, 2014
c65cb45
Copter: move all arm check logic into arm_checks
jschall Oct 10, 2014
6327f4a
Copter: allow arming in GUIDED only from GCS
rmackay9 Oct 11, 2014
77bbd25
AC_PosControl: add force_descend option to set_alt_target_from_climb_…
jschall Nov 14, 2014
f3e9e9c
Copter: use force_descend option on auto landings
jschall Nov 14, 2014
5935082
AC_PosControl: fix to default force_descend param
rmackay9 Nov 14, 2014
44c5fdf
Notify: add pre_arm_gps_check flag
rmackay9 Dec 24, 2014
6b236eb
Copter: set pre_arm_gps_check flag
rmackay9 Dec 24, 2014
152a3a2
ArduCopter: Bug fix, int8t should be uint16t.
R-Lefebvre Jan 6, 2015
1266a31
Rally: reduce distance limit to 300m for copter
rmackay9 Jan 6, 2015
4033f11
Copter: report NAV_CONTROLLER_OUTPUT in RTL, Guided
rmackay9 Jan 6, 2015
105e2e1
Copter: skip pre-arm checks when already armed
rmackay9 Dec 26, 2014
aa1b0da
Copter: run_nav_updates at 100hz on pixhawk
jschall Nov 2, 2014
f5fb21b
Copter: run_nav_updates at 50hz on Pixhawk, 25hz on APM2
rmackay9 Dec 5, 2014
0ad7a39
Copter: import new travis config
tridge Jan 8, 2015
827e60f
AP_InertialSensor: roll up to latest AP_InertialSensor from master
tridge Jan 8, 2015
94f3c64
HAL_SITL: fixed for changes in AP_InertialSensor API
tridge Jan 8, 2015
7b178ef
Copter: fixes for AP_InertialSensor API changes
tridge Jan 8, 2015
fbef07c
Travis: added build script from master
tridge Jan 8, 2015
9b96651
Travis: update to latest prereqs script from master
tridge Jan 8, 2015
f053af5
Travis: only build copter in copter-3.2 branch
tridge Jan 8, 2015
8da5716
Travis: don't build Linux for travis in copter-3.2
tridge Jan 8, 2015
712b95b
AP_HAL: added micros64() method
tridge Jan 8, 2015
e7dcb43
PX4: update to new PX4 config
tridge Jan 8, 2015
3761870
build: update to build rules from master
tridge Jan 8, 2015
b058f3f
AP_InertialSensor: added missing files
tridge Jan 8, 2015
18b6c01
PX4: added px4_common.mk
tridge Jan 8, 2015
113475b
autotest: use small INS offsets so INS is recognised as being calibrated
tridge Jan 4, 2015
c0f5b54
Copter: AC3.2.1-rc1 Release Notes
rmackay9 Jan 8, 2015
6880888
Copter: update version to AC3.2.1-rc1
rmackay9 Jan 8, 2015
43762c9
Copter: increase GPS_HDOP_GOOD default to 2.3
rmackay9 Dec 15, 2014
f1207e0
Copter: update AC3.2.1-rc1 Release Notes
rmackay9 Jan 8, 2015
343dd16
Copter: fix typo in AC3.2.1 Release Notes
rmackay9 Jan 10, 2015
6b0e636
AP_Math: add yaw 293, pitch 68, roll 180 rotation
rmackay9 Nov 22, 2014
4b5411e
AP_Math: add new rotation to example rotation sketch
rmackay9 Nov 22, 2014
eb9b2bf
AP_Math: fixed build warning
Nov 24, 2014
79975b1
AP_Math: change ROTATION_YAW_293_PITCH_68_ROLL_180 to ROLL_90
jschall Dec 31, 2014
2d82672
AC_PosControl: Fill _vel_desired.z for reporting
jschall Jan 12, 2015
ca68a9a
Copter: clean up land detector and modify to use desired velocity
jschall Jan 12, 2015
651a018
Copter: move land_detector to separate file
rmackay9 Jan 14, 2015
3fd38ed
Copter: restore baro climb rate check to land_detector
rmackay9 Jan 14, 2015
0c3f43b
AutoTest: reduce copter throttle when in stabilize
rmackay9 Jan 14, 2015
b010556
AP_Mission: prevent infinite loop with linked jump commands
tridge Jan 23, 2015
fee41be
Copter: version to AC3.2.1-rc2
rmackay9 Jan 30, 2015
ef4ca82
Copter: AC3.2.1-rc2 release notes
rmackay9 Jan 30, 2015
a067a5e
Copter: land detector requires desired climb rate be < -20cm/s
rmackay9 Jan 31, 2015
90961bb
Copter: protect against multiple arming messages
rmackay9 Feb 2, 2015
b32081f
AC_PosControl: Enable altitude limit checking.
R-Lefebvre Jan 28, 2015
e28b7c3
Copter: update pos_control alt_max from fence at 1hz
R-Lefebvre Jan 30, 2015
375b9a5
AC_PosControl: move alt limit to set_alt_target_from_climb_rate
rmackay9 Jan 30, 2015
5f118b2
Copter: update AC3.2.1-rc2 release notes
rmackay9 Feb 3, 2015
dde4184
Copter: AC3.2.1 release notes
rmackay9 Feb 11, 2015
36b405f
Copter: version to AC3.2.1
rmackay9 Feb 11, 2015
03373d3
AutoTest: Add ability to run AC3.2.1 in screen
billbonney Apr 17, 2015
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 9 additions & 4 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,12 @@ before_install:
- cd .. && ./ardupilot/Tools/scripts/install-prereqs-ubuntu.sh -y && . ~/.profile

script:
- cd ./ardupilot/ArduCopter && make configure && make && make px4-v2
- cd ../ArduPlane && make configure && make && make px4-v2
- cd ../APMrover2 && make configure && make && make px4-v2
- cd ../ArduCopter && make configure && make && make vrubrain-v51
- cd ./ardupilot && Tools/scripts/build_all_travis.sh

notifications:
webhooks:
urls:
- https://webhooks.gitter.im/e/e5e0b55e353e53945b4b
on_success: change # options: [always|never|change] default: always
on_failure: always # options: [always|never|change] default: always
on_start: false # default: false
6 changes: 6 additions & 0 deletions APMrover2/GCS_Mavlink.pde
Original file line number Diff line number Diff line change
Expand Up @@ -958,6 +958,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)

case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{
// mark the firmware version in the tlog
send_text_P(SEVERITY_LOW, PSTR(FIRMWARE_STRING));

#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
send_text_P(SEVERITY_LOW, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
#endif
handle_param_request_list(msg);
break;
}
Expand Down
5 changes: 1 addition & 4 deletions ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,6 @@
*/

// uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE. Top items save the most flash space
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_APM1)
# define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
# define FRSKY_TELEM_ENABLED DISABLED // disable the FRSKY TELEM
#endif
//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
//#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash
Expand All @@ -34,6 +30,7 @@
// features below are disabled by default on APM (but enabled on Pixhawk)
//#define AC_RALLY ENABLED // disable rally points to save 2k of flash, and also frees rally point EEPROM for more mission commands
//#define PARACHUTE ENABLED // enable parachute release at a cost of 1k of flash
//#define CLI_ENABLED ENABLED // enable the CLI (command-line-interface) at a cost of 21K of flash space

// features below are disabled by default on all boards
//#define OPTFLOW ENABLED // enable optical flow sensor and OF_LOITER flight mode at a cost of 5K of flash space
Expand Down
15 changes: 15 additions & 0 deletions ArduCopter/AP_State.pde
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,21 @@ void set_land_complete(bool b)

// ---------------------------------------------

// set land complete maybe flag
void set_land_complete_maybe(bool b)
{
// if no change, exit immediately
if (ap.land_complete_maybe == b)
return;

if (b) {
Log_Write_Event(DATA_LAND_COMPLETE_MAYBE);
}
ap.land_complete_maybe = b;
}

// ---------------------------------------------

void set_pre_arm_check(bool b)
{
if(ap.pre_arm_check != b) {
Expand Down
82 changes: 37 additions & 45 deletions ArduCopter/ArduCopter.pde
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#define THISFIRMWARE "ArduCopter V3.2-rc5"
#define THISFIRMWARE "ArduCopter V3.2.1"
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
Expand Down Expand Up @@ -206,6 +206,9 @@ static AP_Notify notify;
// used to detect MAVLink acks from GCS to stop compassmot
static uint8_t command_ack_counter;

// has a log download started?
static bool in_log_download;

////////////////////////////////////////////////////////////////////////////////
// prototypes
////////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -288,25 +291,7 @@ static AP_Compass_HIL compass;
AP_ADC_ADS7844 apm1_adc;
#endif

#if CONFIG_INS_TYPE == HAL_INS_MPU6000
AP_InertialSensor_MPU6000 ins;
#elif CONFIG_INS_TYPE == HAL_INS_PX4
AP_InertialSensor_PX4 ins;
#elif CONFIG_INS_TYPE == HAL_INS_VRBRAIN
AP_InertialSensor_VRBRAIN ins;
#elif CONFIG_INS_TYPE == HAL_INS_HIL
AP_InertialSensor_HIL ins;
#elif CONFIG_INS_TYPE == HAL_INS_OILPAN
AP_InertialSensor_Oilpan ins( &apm1_adc );
#elif CONFIG_INS_TYPE == HAL_INS_FLYMAPLE
AP_InertialSensor_Flymaple ins;
#elif CONFIG_INS_TYPE == HAL_INS_L3G4200D
AP_InertialSensor_L3G4200D ins;
#elif CONFIG_INS_TYPE == HAL_INS_MPU9250
AP_InertialSensor_MPU9250 ins;
#else
#error Unrecognised CONFIG_INS_TYPE setting.
#endif // CONFIG_INS_TYPE
AP_InertialSensor ins;

// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
Expand Down Expand Up @@ -388,6 +373,9 @@ static union {
uint8_t rc_receiver_present : 1; // 14 // true if we have an rc receiver present (i.e. if we've ever received an update
uint8_t compass_mot : 1; // 15 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // 16 // true if we are currently performing the motors test
uint8_t initialised : 1; // 17 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1; // 18 // true if we may have landed (less strict version of land_complete)
uint8_t throttle_zero : 1; // 19 // true if the throttle stick is at zero, debounced
};
uint32_t value;
} ap;
Expand Down Expand Up @@ -571,8 +559,8 @@ static int16_t climb_rate;
static int16_t sonar_alt;
static uint8_t sonar_alt_health; // true if we can trust the altitude from the sonar
static float target_sonar_alt; // desired altitude in cm above the ground
// The altitude as reported by Baro in cm - Values can be quite high
static int32_t baro_alt;
static int32_t baro_alt; // barometer altitude in cm above home
static float baro_climbrate; // barometer climbrate in cm/s


////////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -795,7 +783,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ arm_motors_check, 40, 1 },
{ auto_trim, 40, 14 },
{ update_altitude, 40, 100 },
{ run_nav_updates, 40, 80 },
{ run_nav_updates, 8, 80 },
{ update_thr_cruise, 40, 10 },
{ three_hz_loop, 133, 9 },
{ compass_accumulate, 8, 42 },
Expand All @@ -805,7 +793,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
#endif
{ update_notify, 8, 10 },
{ one_hz_loop, 400, 42 },
{ ekf_check, 40, 2 },
{ ekf_dcm_check, 40, 2 },
{ crash_check, 40, 2 },
{ gcs_check_input, 8, 550 },
{ gcs_send_heartbeat, 400, 150 },
Expand Down Expand Up @@ -863,7 +851,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ arm_motors_check, 10, 10 },
{ auto_trim, 10, 140 },
{ update_altitude, 10, 1000 },
{ run_nav_updates, 10, 800 },
{ run_nav_updates, 4, 800 },
{ update_thr_cruise, 1, 50 },
{ three_hz_loop, 33, 90 },
{ compass_accumulate, 2, 420 },
Expand All @@ -873,7 +861,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
#endif
{ update_notify, 2, 100 },
{ one_hz_loop, 100, 420 },
{ ekf_check, 10, 20 },
{ ekf_dcm_check, 10, 20 },
{ crash_check, 10, 20 },
{ gcs_check_input, 2, 550 },
{ gcs_send_heartbeat, 100, 150 },
Expand Down Expand Up @@ -942,7 +930,7 @@ static void barometer_accumulate(void)

static void perf_update(void)
{
if (g.log_bitmask & MASK_LOG_PM)
if (should_log(MASK_LOG_PM))
Log_Write_Performance();
if (scheduler.debug()) {
cliSerial->printf_P(PSTR("PERF: %u/%u %lu\n"),
Expand All @@ -957,10 +945,7 @@ static void perf_update(void)
void loop()
{
// wait for an INS sample
if (!ins.wait_for_sample(1000)) {
Log_Write_Error(ERROR_SUBSYSTEM_MAIN, ERROR_CODE_MAIN_INS_DELAY);
return;
}
ins.wait_for_sample();
uint32_t timer = micros();

// check loop time
Expand Down Expand Up @@ -1089,7 +1074,7 @@ static void update_batt_compass(void)
compass.set_throttle((float)g.rc_3.servo_out/1000.0f);
compass.read();
// log compass information
if (g.log_bitmask & MASK_LOG_COMPASS) {
if (should_log(MASK_LOG_COMPASS)) {
Log_Write_Compass();
}
}
Expand All @@ -1102,16 +1087,16 @@ static void update_batt_compass(void)
// should be run at 10hz
static void ten_hz_logging_loop()
{
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) {
if (should_log(MASK_LOG_ATTITUDE_MED)) {
Log_Write_Attitude();
}
if (g.log_bitmask & MASK_LOG_RCIN) {
if (should_log(MASK_LOG_RCIN)) {
DataFlash.Log_Write_RCIN();
}
if (g.log_bitmask & MASK_LOG_RCOUT) {
if (should_log(MASK_LOG_RCOUT)) {
DataFlash.Log_Write_RCOUT();
}
if ((g.log_bitmask & MASK_LOG_NTUN) && mode_requires_GPS(control_mode)) {
if (should_log(MASK_LOG_NTUN) && (mode_requires_GPS(control_mode) || landing_with_GPS())) {
Log_Write_Nav_Tuning();
}
}
Expand All @@ -1126,11 +1111,11 @@ static void fifty_hz_logging_loop()
#endif

#if HIL_MODE == HIL_MODE_DISABLED
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST) {
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
Log_Write_Attitude();
}

if (g.log_bitmask & MASK_LOG_IMU) {
if (should_log(MASK_LOG_IMU)) {
DataFlash.Log_Write_IMU(ins);
}
#endif
Expand Down Expand Up @@ -1160,12 +1145,12 @@ static void three_hz_loop()
// one_hz_loop - runs at 1Hz
static void one_hz_loop()
{
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
Log_Write_Data(DATA_AP_STATE, ap.value);
}

// log battery info to the dataflash
if (g.log_bitmask & MASK_LOG_CURRENT) {
if (should_log(MASK_LOG_CURRENT)) {
Log_Write_Current();
}

Expand Down Expand Up @@ -1206,6 +1191,13 @@ static void one_hz_loop()
#if AP_TERRAIN_AVAILABLE
terrain.update();
#endif

#if AC_FENCE == ENABLED
// set fence altitude limit in position controller
if ((fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) {
pos_control.set_alt_max(fence.get_safe_alt()*100.0f);
}
#endif
}

// called at 100hz but data from sensor only arrives at 20 Hz
Expand All @@ -1224,7 +1216,7 @@ static void update_optical_flow(void)
of_log_counter++;
if( of_log_counter >= 4 ) {
of_log_counter = 0;
if (g.log_bitmask & MASK_LOG_OPTFLOW) {
if (should_log(MASK_LOG_OPTFLOW)) {
Log_Write_Optflow();
}
}
Expand All @@ -1248,7 +1240,7 @@ static void update_GPS(void)
last_gps_reading[i] = gps.last_message_time_ms(i);

// log GPS message
if (g.log_bitmask & MASK_LOG_GPS) {
if (should_log(MASK_LOG_GPS)) {
DataFlash.Log_Write_GPS(gps, i, current_loc.alt);
}

Expand Down Expand Up @@ -1334,7 +1326,7 @@ init_simple_bearing()
super_simple_sin_yaw = simple_sin_yaw;

// log the simple bearing to dataflash
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
Log_Write_Data(DATA_INIT_SIMPLE_BEARING, ahrs.yaw_sensor);
}
}
Expand Down Expand Up @@ -1399,13 +1391,13 @@ static void read_AHRS(void)
static void update_altitude()
{
// read in baro altitude
baro_alt = read_barometer();
read_barometer();

// read in sonar altitude
sonar_alt = read_sonar();

// write altitude info to dataflash logs
if (g.log_bitmask & MASK_LOG_CTUN) {
if (should_log(MASK_LOG_CTUN)) {
Log_Write_Control_Tuning();
}
}
Expand Down
11 changes: 7 additions & 4 deletions ArduCopter/Attitude.pde
Original file line number Diff line number Diff line change
Expand Up @@ -151,8 +151,8 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control)
// get_pilot_desired_climb_rate - transform pilot's throttle input to
// climb rate in cm/s. we use radio_in instead of control_in to get the full range
// without any deadzone at the bottom
#define THROTTLE_IN_DEADBAND_TOP (THROTTLE_IN_MIDDLE+THROTTLE_IN_DEADBAND) // top of the deadband
#define THROTTLE_IN_DEADBAND_BOTTOM (THROTTLE_IN_MIDDLE-THROTTLE_IN_DEADBAND) // bottom of the deadband
#define THROTTLE_IN_DEADBAND_TOP (THROTTLE_IN_MIDDLE+g.throttle_deadzone) // top of the deadband
#define THROTTLE_IN_DEADBAND_BOTTOM (THROTTLE_IN_MIDDLE-g.throttle_deadzone) // bottom of the deadband
static int16_t get_pilot_desired_climb_rate(int16_t throttle_control)
{
int16_t desired_rate = 0;
Expand All @@ -165,13 +165,16 @@ static int16_t get_pilot_desired_climb_rate(int16_t throttle_control)
// ensure a reasonable throttle value
throttle_control = constrain_int16(throttle_control,0,1000);

// ensure a reasonable deadzone
g.throttle_deadzone = constrain_int16(g.throttle_deadzone, 0, 400);

// check throttle is above, below or in the deadband
if (throttle_control < THROTTLE_IN_DEADBAND_BOTTOM) {
// below the deadband
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_BOTTOM) / (THROTTLE_IN_MIDDLE - THROTTLE_IN_DEADBAND);
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_BOTTOM) / (THROTTLE_IN_MIDDLE - g.throttle_deadzone);
}else if (throttle_control > THROTTLE_IN_DEADBAND_TOP) {
// above the deadband
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_TOP) / (THROTTLE_IN_MIDDLE - THROTTLE_IN_DEADBAND);
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_TOP) / (THROTTLE_IN_MIDDLE - g.throttle_deadzone);
}else{
// must be in the deadband
desired_rate = 0;
Expand Down
Loading