Commit Graph

29644 Commits

Author SHA1 Message Date
Daniel Agar 58b74e241e px4_fmu-v2 disable mpu9250 2019-07-08 14:49:58 -04:00
Daniel Agar 26f6794aa9 px4_fmu-v2 re-enable CONSTRAINED_FLASH build
- this limits console output at boot
2019-07-08 14:49:58 -04:00
Daniel Agar 15d1543f95 create systemcmds/i2cdetect tool to scan i2c bus 2019-07-06 10:28:16 -04:00
PX4 Build Bot d9c90ed31a Update submodule ecl to latest Fri Jul 5 12:38:36 UTC 2019
- ecl in PX4/Firmware (590b55cb222ec68d4bbb61208f301102607b6161): a036cf82cc
    - ecl current upstream: e1751188fd
    - Changes: a036cf82cc...e1751188fd

    e175118 2019-06-28 bresch - EKF - Initialize _deadrekon_time_exceeded to true. If no sample have been received, deadrekoning and local position should be invalid.
2019-07-05 16:46:31 -04:00
Mathieu Bresciani e54075abe8 MC pos control - Force cruise and manual speeds below max speed. (#12404)
- Force hover thrust between min and max thrust
2019-07-05 15:40:28 -04:00
David Sidrane ea0da3a3b6 px4/fmu-v5x: GPIO ADC had bad definition 2019-07-05 12:23:06 -04:00
RomanBapst 7c8fa82e76 rtl cone angle: expose a few values to the user
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2019-07-05 18:05:09 +02:00
RomanBapst 81ee40eac8 rtl: implemented RTL based on cone shape
- user defines a cone half angle which defines the RTL altitude behavior
- if vehicle is outside the cone it will climb until it intersects the cone
and then return at this altitude.
- if vehicle is inside the cone or above the predefined return altitude (RTL_RETURN_ALT)
then it will return at the current altitude

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2019-07-05 18:05:09 +02:00
Timothy Scott f7a460427b Changed name of mixer to be shorter 2019-07-05 18:00:15 +02:00
CarlOlsson 12fcddd288 fmu: remove unused functions 2019-07-04 22:08:00 -04:00
Silvan Fuhrer 9b46c1d8a9 Upated Babyshark VTOL config and vtol_defaults
Updated the babyshark default  parameters for improved flight performance,
as well as two MPC parameters in vtol_defaults for smoother hovering with VTOLS"

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2019-07-04 11:26:01 -04:00
Nicolas de Palezieux 2f1cfa60f4 precland: store result of _target_pose_sub.update() for later use
- Fixes #12391
2019-07-04 11:02:14 -04:00
BazookaJoe1900 72a449490a Mavlink: Use MAV_BROADCAST only in context of ethernet 2019-07-03 14:02:37 -04:00
Fabian Schilling d139bc5a7c Use bc to support floating point PX4_SIM_SPEED_FACTOR 2019-07-03 16:54:29 +02:00
Timothy Scott dce1dda871 Fixed incorrect timestamps 2019-07-03 14:39:59 +02:00
Beat Küng a2471fb539 logger: handle 'char' type in messages
Fixes errors like:
ERROR [logger] No definition for topic char[10] key;uint8_t[2] _padding0; found
when the Debug logging profile is selected.
2019-07-03 10:43:59 +02:00
alessandro fecb32f88d
Parameter for virtual battery in SITL (#12299)
* New parameter for virtual battery in SITL

* Update src/modules/simulator/simulator_mavlink.cpp

Co-Authored-By: Beat Küng <beat-kueng@gmx.net>

* Updated description for parameter SIM_BAT_MIN_PCT
2019-07-02 15:53:18 +02:00
Daniel Agar 9bfc4f2d54
Analog Device ADIS16477 move to PX4Accelerometer/PX4Gyroscope and cleanup 2019-07-01 22:53:27 -04:00
Daniel Agar 9450496eb4
Analog Devices ADIS16497 move to PX4Accelerometer/PX4Gyroscope and cleanup 2019-07-01 22:47:31 -04:00
Daniel Agar cdadb393b7
Analog Device ADIS16448 cleanup
- move to PX4Accelerometer, PX4Gyroscope, PX4Magnetometer helpers
 - add barometer support (using PX4Barometer)
2019-07-01 16:02:00 -04:00
dlwalter cbdfc0c587 px4_fmu-v5: rc.board_sensors start lis3mdl optional external magnetometer 2019-07-01 14:52:14 -04:00
Daniel Agar 6ef61e5c19 landing_target_estimator: update to uORB Subscription and Publication 2019-07-01 10:35:41 -04:00
Daniel Agar 38da0f95aa rc_input move to uORB::Subscription 2019-07-01 10:35:26 +02:00
Daniel Agar 4f445cd7f8 vscode add av_x-v1 debug target 2019-06-30 19:05:54 -04:00
Daniel Agar 7f9415ba46 systemcmds/top: increase stack 200 bytes
- this is necessary after most boards increased CONFIG_MAX_TASKS 32 -> 64
2019-06-30 18:37:41 -04:00
Daniel Agar d1298f2c37 Jenkins HITL exit upload monitor on nsh> 2019-06-29 17:18:22 -04:00
Daniel Agar c165a6f71b attitude_estimator_q: move most orb subscriptions to uORB::Subscription 2019-06-29 15:51:49 -04:00
Mark Sauder 423219c60e pga460: Change variable initialization to uniform initialization style, format whitespace, and change baud rate unsigned to speed_t type. (#11861) 2019-06-28 21:52:16 -04:00
Mark Sauder db96b6c08d cm8jl65: Refactor driver, employ uniform initialization, format, and deprecate ringbuffer and IOCTL. (#11853)
* Move cm8jl65 class member variable initialization from constructor list to declarations.  Format whitespace and move method doxy comments  to declarations.

* Refactor the cm8jl65 driver start() method, and rename info()->status().

* Continued refactoring of the cm8jl65 driver class:
 - Condense all class files into a single *.cpp file and give class scope resolution to previously unscoped methods.
 - Refactor cm8jl65 namespace level driver entry methods to reduce code and improve clarity.
 - Breakout CDev specific initialization LOC into the device_init() method.
 - Move the endian modification inside of the crc16_calc() method.

* Deprecate the hardware ringbuffer, _class_instance, and ioctl() from the cm8jl65 driver.
2019-06-28 21:46:02 -04:00
Daniel Agar 4b778fd0c2
navigator: fix vehicle_status update (#12364) 2019-06-28 21:35:29 -04:00
Mark Sauder 5857cf4799 LeddarOne: Refactor the driver to standardize against other distance sensor drivers. (#11858)
* Migrate remaining member variable intialization to declarations and employ uniform initialization style. Copy/paste help() and main() methods to the bottom of the file to match convention with other distance sensor drivers.

* Refactor the LeddarOne driver class to give scope resultion to the methods that were global and to standardize the implementation against most of the other distance sensor drivers.

* Deprecate _reports member var, use of hardware ring buffer, and LeddarOne::read() method.

* Deprecate commented (dead) code from the LeddarOne class init() method.

* Refactor the LeddarOne class cycle() and collect() methods and create measure() method to untangle the previous logic implementation.
2019-06-28 21:29:44 -04:00
PX4 Build Bot 309322ce98 Update submodule sitl_gazebo to latest Fri Jun 28 12:37:57 UTC 2019
- sitl_gazebo in PX4/Firmware (7bba5a7287): 95adbb11f8
    - sitl_gazebo current upstream: 22df9475ca
    - Changes: 95adbb11f8...22df9475ca

    22df947 2019-06-27 Martina Rivizzigno - Range.proto: fix indentation
8ef5625 2019-05-28 Martina Rivizzigno - update sonar message to match mavlink distance sensor definition
e04ff96 2018-12-04 Martina - get distance sensor orientation from the vehicle model instead of hard-coding it in the gazebo interface, add horizontal and vertical fov
2019-06-28 16:43:49 +01:00
Daniele Pettenuzzo 55b5e7552c mavlink: add new extvisionmin mode (#12279)
Signed-off-by: DanielePettenuzzo <daniele@px4.io>
2019-06-28 10:44:22 -04:00
Mark Sauder c22ed9397e land_detector: Implement ModuleParams inheritance in the FixedwingLandDetector class. 2019-06-28 10:26:59 -04:00
RomanBapst 0b2af5c519 FixedWingAttitudeControl: don't lock integrator during transition
- airframes that are not well trimmed rely on the integrator to learn
the offset. This change can help improve altitude hold during transitions

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2019-06-28 09:54:40 -04:00
RomanBapst 7bba5a7287 vtol_configs: replaced VT_MOT_COUNT with VT_MOT_ID
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2019-06-27 20:14:10 +02:00
RomanBapst afd95b14cf vtol_att_control: use VT_MOT_ID instead of VT_MOT_COUNT
- VT_MOT_COUNT assumed that motors were always the first outputs. This
does not have to be true always. VT_MOT_ID allows to specify precisely how
many motors we have for hovering and to which channel they are connected.

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2019-06-27 20:14:10 +02:00
RomanBapst 2c74216028 ekf2: fixed calculation of static pressure error
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2019-06-27 18:11:53 +02:00
Mark Sauder 1466d11acc land_detector: cleanup actuator_armed and battery_status naming
* Rename _arming -> _actuator_armed
 * Rename _battery -> _battery_status in the MulticopterLandDetector class.
2019-06-27 12:02:14 -04:00
Mark Sauder 94c1f21473 mb12xx: Refactor driver class to allow for multiple sensors and cleanup (#11859)
* Migrate mb12xx driver class member variable initialization to declarations.
Format whitespace and alphabetize/group/order var declarations.
Refactor driver reset() and mb12xx_main() methods for readability.
Deprecate usage of IOCTL.

* Deprecate the _reports ringbuffer, _class_instance, and read() method and minor formatting in the mb12xx driver.

* Add time_literal usage and #define MB12XX_BUS_SPEED.

* Refactor the mb12xx driver to mirror the mappy_dot driver implementation and create functionality for multiple sensors.

* Add stack size for the mb12xx driver.
2019-06-27 11:59:40 -04:00
Mathieu Bresciani c5deba53a2 mc_pos_control: Explicitly convert tilt variables to radians during check and assignments 2019-06-27 11:38:21 -04:00
Lorenz Meier 748ff7f50a
Update README.md
Clarify the naming of FMU versions to not confuse users once the new industrial FMUv5X standard is established.
2019-06-27 08:28:32 +02:00
Anthony Lamping 49966f4c46 launch: multiple sdf models (#12306) 2019-06-26 15:20:49 -04:00
David Sidrane 6fcc4cc6a2 WIP Digital PM Support 2019-06-26 14:34:02 -04:00
David Sidrane 1cf4a2d953 Added Suport for ICM 20602 on PX4_SPI_BUS_SENSORS1 2019-06-26 14:34:02 -04:00
David Sidrane e5b6adc7f3 fmu-v5X VER REV Combined 2019-06-26 14:34:02 -04:00
David Sidrane 31dfaee76a fmuv5x board support 2019-06-26 14:34:02 -04:00
mcsauder 6e9f706b12 Standardize remaining class member variable naming convention in the MulticopterLandDetector class. 2019-06-26 14:06:56 -04:00
mcsauder df662245a2 Standardize class member variable naming convention in the LandDetector class. 2019-06-26 14:06:56 -04:00
mcsauder 6b6d82447e Standardize class member variable naming convention in the MulticopterLandDetector class. 2019-06-26 14:06:56 -04:00