Commit Graph

5544 Commits

Author SHA1 Message Date
Robert Lefebvre 92bdf24dba AP_MotorsHeli: Add To-Do. Swash setup hasn't seemed to work right for a while, this might be why. Confirm later. 2014-07-13 17:11:22 +09:00
Robert Lefebvre a7f6a91827 AC_AttitudeControl_Heli: Remove ToDo. Rate controllers should always run even if throttle is zero. 2014-07-13 17:11:20 +09:00
Randy Mackay f630f9abc3 GPS: exclude SIRF and NMEA on APM copter build
This only works for the centralised builder, the modified Arduino IDE
will still include the NMEA and SIRF drivers meaning it will require
approximately 4k additional flash which may push us over the limit on
the APM2.  Users will instead need to exclude other features to get
below the APM1/2 flash limit.
2014-07-13 15:41:11 +09:00
Andrew Tridgell ddb030088d GCS_Mavlink: moved some more mavlink functions to GCS_Common.cpp 2014-07-13 15:37:49 +10:00
Randy Mackay 971411e0db AC_AttControl: fixed typo in parameter description 2014-07-13 10:31:11 +09:00
Randy Mackay 5f623ac859 AC_AttControl: re-enable rate feedforward by default
Roll and Pitch rate controllers became sluggish without feed-forward
enabled.
2014-07-11 15:31:00 +09:00
Randy Mackay bbf4805b0e Compass: update pixhawk expected device ids 2014-07-11 11:10:18 +09:00
Craig Elder c9f3adcb5c Compass: Updated COMPASS_PRIMARY parameter description 2014-07-10 15:32:06 -07:00
Craig Elder 0ecd12b1c6 AP_Compass: Corrected typo in parameter description
Corrected typo in parameter description
2014-07-10 14:19:19 -07:00
Randy Mackay fa2f5d9c68 Arming: accept non-const compass in constructor
The compass.configured() method checks the eeprom and cannot be const
meaning the Arming object requires a non-const reference to the compass.
Removed check for null compass because the compass object is always
created although this could lead to unnecessary pre-arn check failures
even though compass-use is set to false.
2014-07-10 22:50:52 +09:00
Randy Mackay 4995b9ada8 Compass: default device id to zero 2014-07-10 20:25:36 +09:00
Randy Mackay 16d4af8346 Compass: sanity check instance in set_and_save_offsets 2014-07-10 20:25:32 +09:00
Randy Mackay 76369d153f Arming: use compass.configured method
This checks that when compass offset learning is off, that the offsets
are non-zero and that the detected device id matches the device id
stored to eeprom when the offsets were last saved.
2014-07-10 20:25:30 +09:00
Randy Mackay cf7e1a6339 Compass: example sketch update for set_and_save_offsets 2014-07-10 20:25:13 +09:00
Randy Mackay a778522cef Compass: add learn_offsets_enabled accessor method 2014-07-10 20:25:11 +09:00
Randy Mackay 108c878b04 Compass: set_offsets modified to also save offsets 2014-07-10 20:25:08 +09:00
Randy Mackay 124bd4b489 Compass: save_offsets accepts compass instance 2014-07-10 20:25:05 +09:00
Randy Mackay 2c1fa5f1e8 GCS_MAVLink: generate after adding deprecated note to SET_MAG_OFFSETS 2014-07-10 20:25:02 +09:00
Randy Mackay 798c749833 GCS_MAVLink: add deprecated note to SET_MAG_OFFSETS 2014-07-10 20:25:00 +09:00
Randy Mackay 05225636da GCS_MAVLink: generate after adding second mag to PREFLIGHT_SET_SENSOR_OFFSETS 2014-07-10 20:24:58 +09:00
Randy Mackay bf6fd6f984 GCS_MAVLink: add second mag to PREFLIGHT_SET_SENSOR_OFFSETS
Updates the comments for parameter 1 only, this does not affect the
message format.
2014-07-10 20:24:55 +09:00
Randy Mackay 070f1c1bbb Compass: add dev_id for VRBrain 2014-07-10 20:24:49 +09:00
Randy Mackay f42c9579d7 Compass: add dev_id for PX4
dev_id is retrieved from PX4Firmware via ioctl call
2014-07-10 20:24:46 +09:00
Randy Mackay b7f33d81ad Compass: add DEV_ID param and configured method
These allow checking the offsets were created with the current compass
device.
2014-07-10 20:24:44 +09:00
svefro be9bfc5530 Mount: set_mode method made public 2014-07-10 13:03:43 +09:00
Andrew Tridgell d325f630e5 VibTest: added sample timing to console output 2014-07-09 12:12:23 +10:00
Andrew Tridgell 8af876fe8a AC_AttitudeControl: fixed build
includes are case sensitive on the build server
2014-07-09 10:19:17 +10:00
Andrew Tridgell 863e7a5f93 VibTest: fixed array bounds error 2014-07-09 08:11:52 +10:00
Andrew Tridgell 2c8240dbb4 VibTest: fixed gyro timestamps in logs
it was using the accel timestamps
2014-07-09 08:10:09 +10:00
Robert Lefebvre 789b1018fc AP_MotorsHeli: Change set_delta_phase_angle so that it forces recalculation of collective factors. 2014-07-08 20:18:39 +09:00
Robert Lefebvre fd542e99d8 AP_MotorsHeli: Create Delta Phase Angle variable and method to set. Will be used by CCComp code. 2014-07-08 20:18:34 +09:00
Robert Lefebvre 0680b88abd AP_MotorsHeli: Add main loop rate time variable and method. Change RSC increment calc to account for loop rate time. 2014-07-08 20:18:20 +09:00
Robert Lefebvre 26be7aed97 AC_AttControl_Heli: Add LPF filter to Rate Feedforward terms 2014-07-08 20:18:13 +09:00
Robert Lefebvre fa9d625e39 AC_HELI_PID: Add feedforward accessor functions. 2014-07-08 20:18:05 +09:00
Robert Lefebvre 979abb9fbd TradHeli: Cause DDVP Tail Motor to stop immediately when Ch8 is 0. 2014-07-08 20:18:02 +09:00
Andrew Tridgell b2bc098aee HAL_PX4: avoid some float conversion warnings 2014-07-08 20:27:19 +10:00
Andrew Tridgell e137bf26ef HAL_Empty: avoid some float conversion warnings 2014-07-08 20:27:13 +10:00
Andrew Tridgell 59de5a8465 AP_GPS: avoid some float conversion warnings 2014-07-08 20:27:03 +10:00
Andrew Tridgell 74c3b404ee AP_Baro: avoid some float conversion warnings 2014-07-08 20:26:54 +10:00
Andrew Tridgell 6b87c9fdf7 AP_Airspeed: avoid some float conversion warnings 2014-07-08 20:26:44 +10:00
Andrew Tridgell f28946defb AP_ADC_AnalogSource: avoid some float conversion warnings 2014-07-08 20:26:37 +10:00
Andrew Tridgell 198ada2b42 APM_Control: avoid some float conversion warnings 2014-07-08 20:26:20 +10:00
Andrew Tridgell baa0217bec AP_RangeFinder: trigger a new reading automatically
this fixes Maxbotix I2C
2014-07-08 16:28:18 +10:00
Andrew Tridgell f6d9bc5d7e AP_RangeFinder: fixed detection of multiple types
Pair-Programmed-With: Allyson Kreft
2014-07-08 15:08:18 +10:00
Andrew Tridgell 7ceb14bec0 HAL_Empty: make I2C ops fail 2014-07-08 15:08:18 +10:00
Andrew Tridgell 9386295428 AP_RangeFinder: added SONAR2_TYPE parameter
thanks to Allyson for noticing
2014-07-08 15:08:18 +10:00
Andrew Tridgell 05d4f5fb5a AP_RangeFinder: convert PX4 driver to new API 2014-07-08 15:08:18 +10:00
Andrew Tridgell 4cba48ade2 AP_RangeFinder: removed old style analog drivers
replaced by generic analog driver
2014-07-08 15:07:51 +10:00
Andrew Tridgell ed346fd639 AP_RangeFinder: convert MaxbotixI2C driver to new API 2014-07-08 15:07:51 +10:00
Andrew Tridgell 0063d83dbc AP_RangeFinder: convert the PulsedLight driver to new API
not tested yet
2014-07-08 15:07:50 +10:00
Andrew Tridgell 22b9059647 AP_RangeFinder: have two instances on all platforms
rover needs two sonars for obstacle avoidance
2014-07-08 15:07:50 +10:00
Andrew Tridgell e69a473315 SITL: update simulated sonar support 2014-07-08 15:07:50 +10:00
Andrew Tridgell 6f33ca4988 AP_RangeFinder: added SONAR_RMETRIC option
this allows correct support for non-ratiometric rangefinders such as
the SF/02
2014-07-08 15:07:50 +10:00
Andrew Tridgell 92b76b4be4 AP_RangeFinder: converted analog rangefinder backend to new API
this gets analog rangefinders of all types working
2014-07-08 15:07:50 +10:00
Andrew Tridgell cb037f3416 AP_RangeFinder: new rangefinder API ready for its first backend
the backends are setup to have just the minimum functionality needed
for a rangefinder, with all of the higher level logic in the
frontend. This should make writing a new backend easier
2014-07-08 15:07:50 +10:00
Andrew Tridgell 429431157b AP_RangeFinder: disable old rangefinder drivers
these will be re-enabled when they are converted to the new class API
2014-07-08 15:07:50 +10:00
akdslr d759a9dd9b AP_RangeFinder: Seperated the Backend driver functionality into a separate class 2014-07-08 15:07:49 +10:00
akdslr 3f17969b19 AP_RangeFinder: Changes from the May 4th plane test flight 2014-07-08 15:07:49 +10:00
akdslr 2e586ccfb2 AP_RangeFinder_PulsedLightLRF: Updated the value to write to the register to trigger a measurement 2014-07-08 15:07:49 +10:00
akdslr 5f4168d5f8 AP_RangeFinder_PX4_test: Added an example sketch for the PX4 range finder 2014-07-08 15:07:49 +10:00
akdslr 18c06277f8 AP_RangeFinder: Added a new PX4 range finder and modified the RangeFinder parent class to support having multiple devices simultaneously 2014-07-08 15:07:49 +10:00
akdslr a2df275bd9 AP_RangeFinder_PulsedLightLRF: Updated the register definitions for the new hardware 2014-07-08 15:07:49 +10:00
Andrew Tridgell e118984c26 AP_Baro: save some flash and memory on APM2
we don't need the I2C MS5611 driver
2014-07-08 14:21:42 +10:00
Andrew Tridgell d50d5b8f24 VibTest: fixed sample count output on console 2014-07-08 10:59:30 +10:00
Andrew Tridgell 03770c4d34 VibTest: added gyro data and support 3 sensors
will be used for vibration testing on FMUv3
2014-07-08 10:07:58 +10:00
Randy Mackay 2b64c511ed AC_WPNav: update yaw only when track is at least 2m 2014-07-06 17:02:12 +09:00
Randy Mackay c9661cfb09 AC_WPNav: integrate set_desired_velocity_xy function name change 2014-07-06 17:01:10 +09:00
Randy Mackay 82ed70b25e AC_PosControl: add xyz velocity controller
Velocity controller interpretsthe velocity requests as
desired velocities (i.e. feed forward).  These are then used to update
the target position and also added to the target velocity.
Also renamed the set_desired_velocity() function to
set_desired_velocity_xy() to make clear only lat and lon axis are
updated.
2014-07-06 17:01:02 +09:00
Randy Mackay fe8a5be802 AP_Mission: support MAV_CMD_NAV_VELOCITY msg 2014-07-06 17:01:00 +09:00
Randy Mackay 34b91496f9 GCS_MAVLink: generate after adding CMD_NAV_VELOCITY 2014-07-06 17:00:57 +09:00
Randy Mackay 35167c262e GCS_Mavlink: add MAV_CMD_NAV_VELOCITY
This is an earth frame velocity request message
2014-07-06 17:00:55 +09:00
Randy Mackay 9103899048 GCS_Common: minor typo in comments 2014-07-06 17:00:52 +09:00
Randy Mackay f4c9d58051 AP_Mission: add support for MAV_CMD_NAV_GUIDED 2014-07-06 17:00:26 +09:00
Randy Mackay be003c1906 GCS_MAVLink: generate after adding CMD_NAV_GUIDED 2014-07-06 17:00:24 +09:00
Randy Mackay 05c63592ce GCS_MAVLink: add CMD_NAV_GUIDED to ardupilotmega.xml 2014-07-06 17:00:21 +09:00
Andrew Tridgell c138244155 AP_Compass: support 3 mags on PX4 2014-07-04 12:07:47 +10:00
Emile Castelnuovo b420a5c6db AP_HAL_VRBRAIN: removed empty lines 2014-07-03 11:09:20 +10:00
Niels Joubert fabd7601f0 GPS: Fix dataflash logging bug in SBP driver 2014-07-03 09:57:10 +10:00
Niels Joubert b57d1f5245 GPS: Include 75-class CPUs in RTK support since they will have 64 bit floating point values. 2014-07-03 09:57:07 +10:00
Andrew Tridgell 849c4905fb HAL_PX4: print overtime message on stuck task
this should make it easier to narrow down stuck task bugs
2014-07-03 09:11:24 +10:00
Andrew Tridgell 67f5ba0b94 AP_Scheduler: added current_task static
will be used to debug stuck tasks on PX4
2014-07-03 09:09:11 +10:00
Emile Castelnuovo bdd9fe77c7 VRBRAIN: change default pin for analog input. 2014-07-01 12:23:25 +02:00
LukeMike f70da39206 VRBRAIN: changed the management of the pwm output 2014-07-01 12:21:36 +02:00
LukeMike fa4fffc878 VRBRAIN: deleted unnecessary customizations 2014-07-01 12:21:35 +02:00
Emile Castelnuovo b2680984a5 AP_HAL_VRRBAIN: added comment 2014-07-01 12:21:34 +02:00
Andrew Tridgell bed5db35c7 GCS_MAVLink: fixed missing header 2014-07-01 14:57:41 +10:00
Andrew Tridgell 4c22aa20ad GCS_MAVLink: regenerate headers 2014-07-01 14:26:44 +10:00
Andrew Chapman 7cdd5a700b CameraFeedback: alt rel/msl, renamed CAMERA_EVENT
- include both “alt_msl” and “alt_rel”
- rename CAMERA_EVENT to CAMERA_STATUS
- clarify comments regarding message origin and order
- change pitch/roll/yaw to be camera rather than vehicle, earth frame
2014-07-01 14:25:55 +10:00
Andrew Tridgell 544d872d65 GCS_MAVLink: fixed a shadowed variable 2014-07-01 09:18:20 +10:00
Andrew Tridgell 773bc7bcbe GCS_MAVLink: added missing RTK headers 2014-06-30 20:06:34 +10:00
Andrew Tridgell f9d87bcc88 AP_GPS: fixed build errors and warnings in SBP driver
shadowed variables and implied casts in structures
2014-06-30 11:15:51 +10:00
Andrew Tridgell bcb3d1af14 GCS_MAVLink: fixed flymaple build
has dual GPS but no RTK support
2014-06-30 10:51:19 +10:00
Andrew Tridgell fc11deb547 GCS_MAVLink: regenerate headers 2014-06-30 10:31:11 +10:00
Niels Joubert fa78634959 AP_GPS: GPS calculates MAVLink messages for GPS and GPS_RTK 2014-06-30 10:30:16 +10:00
Niels Joubert baf0697f48 GCS_MAVLink: Add support for GPS_RTK messages 2014-06-30 10:30:16 +10:00
Niels Joubert ad5311c089 MAVLink: New message definitions for GPS_RTK 2014-06-30 10:29:57 +10:00
Niels Joubert 2b1169b0ab AP_GPS: SwiftNav RTK Driver and GPS AutoSwitch param 2014-06-30 10:29:56 +10:00
Niels Joubert fee79c5bac SITL: Piksi Heartbeat Message support, Integer-RTK baseline simulation 2014-06-30 10:29:56 +10:00
Niels Joubert a251d0010a AP_NOTIFY: RTK GPS visual notification through faster blink 2014-06-30 10:29:56 +10:00
Niels Joubert 398f32d538 AP_Math: Comments on WGS coordinate conversions 2014-06-30 10:29:56 +10:00
Andrew Tridgell 1ed716976c GCS_MAVLink: regenerate mavlink headers 2014-06-30 08:25:16 +10:00
Andrew Chapman c6a76e8d97 CameraFeedback: added CAMERA_FEEDBACK_FLAGS for open/closed loop
This is so a GCS can tell if a certain picture was definitely captured
(e.g. with a CCB or machine vision cam) or only requested in the blink
(e.g. uni-directional CHDK)
2014-06-30 08:24:38 +10:00
Andrew Tridgell fd87f28a07 DataFlash: save some flash space on APM2
don't include log message headers that are not used on APM2
2014-06-30 07:58:42 +10:00
Andrew Tridgell e6d8e329d5 DataFlash: allow logging of 3 accels/gyros 2014-06-30 07:58:30 +10:00
Andrew Tridgell ca12592448 AP_InertialSensor: allow for 3 accels and 3 gyros on Pixhawk
this supports FMUv3
2014-06-30 07:58:27 +10:00
Andrew Tridgell ece01da10e AP_InertialSensor: fixed _dump_registers() for MPU6000
need to take the semaphore to prevent bus errors
2014-06-29 12:11:21 +10:00
lthall 4072fcd99e Inav: use horizontal body frame for accel corrections 2014-06-21 14:58:59 +09:00
Emile Castelnuovo 8f3a4bc88b VRBRAIN: correction to AP_Compass_VRBRAIN.cpp 2014-06-19 11:27:45 +02:00
Emile Castelnuovo 946a461873 VRBRAIN: added VRBRAIN to #if 2014-06-19 11:27:44 +02:00
LukeMike 8f552d5758 VRBRAIN: Changed the management of VirtualRobotix's boards. 2014-06-19 11:27:38 +02:00
Michael Oborne 30a3927ea8 AP_Mount: fix where status_msg() is sent
send to the channel where the trigger msg was sent from
2014-06-18 12:03:18 +10:00
svefro b473f8fd4d AP_RCMapper: Added warning to RCMAP_THROTTLE
Warning user that changing RCMAP_Throttle could be dangerous
2014-06-17 21:04:19 +10:00
Randy Mackay 9b81e46e61 AP_Common: add example sketch 2014-06-17 20:53:53 +10:00
Randy Mackay 2f7dee3ba5 AP_Mission: squeeze loiter turns radius into high byte of p1 2014-06-17 20:53:50 +10:00
Randy Mackay b79f729540 AP_Common: add LOWBYTE, HIGHBYTE macros 2014-06-17 20:53:47 +10:00
Randy Mackay fa16e0967f AP_Common: remove unused location mask definitions 2014-06-17 20:53:45 +10:00
Andrew Tridgell e2fe3d2de7 GCS_MAVLink: re-generate headers 2014-06-17 20:21:54 +10:00
Andrew Tridgell 0db226daf5 GCS_MAVLink: merge in upstream changes 2014-06-17 20:19:35 +10:00
Andrew Chapman 87fcfbf9dd GCS_MAVLink: re-generate MAVLink headers 2014-06-17 20:16:39 +10:00
Andrew Chapman 048767e389 GCS_MAVLink: camera feedback mavlink messages
CAMERA_EVENT and CAMERA_FEEDBACK messages, and a couple of enums they
use (CAMERA_EVENT_TYPES and CAMERA_FEEDBACK_FLAGS)

Adjusted some types and added more explicit descriptions of units as
suggested on the call last week.

I will add camera parameter list/get/set functionality as suggested
using the existing parameter mechanism and component IDs rather than
the new CAMERA_INFO messages I had proposed.
2014-06-17 20:15:20 +10:00
Randy Mackay 11e08e1492 DataFlash: common Log_Write_Camera
pair programmed with Craig Elder
2014-06-17 14:11:36 +10:00
Randy Mackay 0c9a496262 AC_AttControlHeli: add ATC_RATE_FF_ENAB parameter
Because this class inherits from AC_AttitudeControl library this new
parameter must be added here as well
2014-06-10 21:25:33 +09:00
Randy Mackay 46f25c52a4 AC_AttControl: allow enabling/disabling feedforward and accel limiting 2014-06-10 20:03:02 +09:00
Randy Mackay a2f54fdf2c AC_WPNav: smooth waypoint by freezing feed-forward and allowing overshoot
First part of this fix is freezing the position controller's xy-axis
feed foward as we transition to the new segment.
Second part is work-around for straight line segments in that we allow
the target point to actually overshoot the end of the segment by up to
2m if the segment is a "fast waypoint".  Ideally we would instead notice
the waypoint has been completed and take any left over time or distance
and move our target along the track towards the next waypoint but that
would require a much larger change to allow the wpnav lib to hold the
next two waypoints.
2014-06-10 20:03:01 +09:00
Randy Mackay ce85d1f6b2 AC_WPNav: use curr pos target as spline origin
We only use the current target position as origin if the waypoint
controller is active (i..e has been used in the past 1 second).  This is
consistent with how we initialise straight line waypoints
2014-06-10 20:02:59 +09:00
Randy Mackay 130eb07d48 AC_AttControl: angle_ef_roll_pitch_rate_ef_yaw supports zero yaw accel 2014-06-10 20:02:58 +09:00
Randy Mackay 02b4b21f67 AC_AttControl: disable feed forward by default
Can be re-enabled by setting ATC_RATE_FF_ENAB parameter to 1
2014-06-10 20:02:55 +09:00
Randy Mackay b57c0dabf6 AC_AttControl: check accel_rp_max instead of rate_bff_ff_enabled
We use the accel_rp_max, accel_y_max to check whether to apply accel
limiting or not.  This is related to separate from the
body-frame-feed-forward.
2014-06-10 20:02:54 +09:00
Randy Mackay 2bb30b3ef9 AC_AttControl: add set_yaw_target_to_current_heading method 2014-06-10 20:02:49 +09:00
Randy Mackay d9c966c927 AC_AttControl: RATE_FF_ENAB param to disable rate feed forward 2014-06-10 20:02:48 +09:00
Randy Mackay 4d4c7a2118 AC_AttControl: move freeze_ff to flags structure 2014-06-10 20:02:46 +09:00
Randy Mackay a662f87ffb AC_AttControl: remove resolved To-Do
This To-Do is resolved by heli flight modes calling the
relax_bf_rate_controller method
2014-06-10 20:02:45 +09:00
Randy Mackay 7f734f38d6 AC_AttControl: add earth frame angle constraints
This should help recovery time if pilot switches out of ACRO (into
Stabilize, AltHold, etc) while inverted
2014-06-10 20:02:43 +09:00
Randy Mackay 698cf934b8 AC_AttControl: formatting fixes 2014-06-10 20:02:42 +09:00
lthall 2bb63857fa AC_AttControl: clean up stabilize 2014-06-10 20:02:40 +09:00
lthall c24d293e1b AC_AttControl: zero _accel_xyz_max stops feed forward
Also added place holder for turning off feed forward.
2014-06-10 20:02:39 +09:00
lthall 8bbce7e658 AC_PosControl: freeze feed forward for alt control in Auto 2014-06-10 20:02:36 +09:00
lthall 922026c15c AC_AttControl: rate compensation for yaw 2014-06-10 20:02:34 +09:00
lthall 0d87298221 AC_PosControl: freeze feed forward and vector fixes 2014-06-10 20:02:33 +09:00
Randy Mackay 5209598459 AC_AttControl: rename init_targets to relax_bf_rate_controller 2014-06-10 20:02:27 +09:00
lthall 1bdde31f6b Copter: Fix zero throttle flip issue Stabilize
The problem is that the init_targets is intended to ensure the
controller doesn't build up the I term when the throttle is low. Because
it is poorly named (or used) it have been written to do something else.
Here I change it to do what the code is trying to use it to do.
2014-06-10 20:02:01 +09:00
Randy Mackay 915dad2da4 AC_Circle: use fast_atan2 to calc bearing from center
This does not save much time because it's only called at initialisation
2014-06-06 18:51:09 +09:00
Randy Mackay f23e94707c AC_WPNav: use fast_atan2 for bearing calcs 2014-06-06 18:51:08 +09:00
David Dewey 17374ff5e8 AP_Math: fast_atan2
This is 126us per call vs 199us on the AVR.  it is accurate to about
0.28 degrees

Committed by rmackay9 but contribution is from David Dewey
2014-06-06 18:50:41 +09:00
Ju1ien 28ce66f314 INav: clear historic z-axis position estimate when set_altitude called 2014-06-06 18:42:42 +09:00
Randy Mackay efd6d6dc70 AC_WPNav: spline div by zero fix
Also add check for straight line navigation to ensure speed is not
reduced below zero when it hits the leash limit
Also minor formatting changes
2014-06-05 22:23:38 +09:00
lthall 0912bec8f5 Spline div zero and leash limit fix 2014-06-05 22:23:35 +09:00
Andrew Tridgell f0df912a11 AP_Mission: added support for MAV_CMD_DO_INVERTED_FLIGHT 2014-06-05 15:44:18 +10:00
Andrew Tridgell ef4a79cc9a GCS_MAVLink: rebuild MAVLink headers 2014-06-05 15:44:03 +10:00
Andrew Tridgell 67937b5b79 GCS_MAVLink: added MAV_CMD_DO_INVERTED_FLIGHT
used to invert from a mission
2014-06-05 15:43:46 +10:00