Commit Graph

1270 Commits

Author SHA1 Message Date
Silvan Fuhrer 92f2043d8b TECS: add EAS_sp to tecs_status.msg and rename other airspeeds to TAS
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-01-23 09:34:34 -05:00
David Sidrane 1414c02471 msg:led_control Extend to support 8 LEDS 2021-01-23 09:30:59 -05:00
Matthias Grob 65884960fa Remove ancient submodules
that were accidentally added back without URL in #16471
2021-01-21 10:46:29 +01:00
TheLegendaryJedi e450c5a9d9 [UPDATE] - Crazyflie parameter config 2021-01-20 19:51:45 +01:00
Mathieu Bresciani 8d8b58efc3
Add logging of mag calibration data (mag_worker_data)
Co-authored-by: Julian Kent <julian@auterion.com>
2021-01-20 09:44:45 -05:00
Beat Küng 25f3fe8456 fix control_allocator_status: torque_setpoint_achieved and thrust_setpoint_achieved are bool 2021-01-18 11:25:37 -05:00
Julien Lecoeur 343cf5603e initial control allocation support
- control allocation module with multirotor, VTOL standard, and tiltrotor support
 - angular_velocity_controller
 - See https://github.com/PX4/PX4-Autopilot/pull/13351 for details

Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
Co-authored-by: Roman Bapst <bapstroman@gmail.com>
2021-01-18 11:25:37 -05:00
Julian Kent d965f1cbc0 Add rtl_flight_time message 2021-01-18 16:26:53 +01:00
Julian Kent 67082ccb2b Test the vehicle type parameter usage 2021-01-18 16:26:53 +01:00
Julian Kent e847ef1a4d Add trig tests for wind calculations, and fix bugs / edge cases 2021-01-18 16:26:53 +01:00
Julian Kent 7482413005 Add Range-based RTL 2021-01-18 16:26:53 +01:00
TSC21 920d6d84b5 rtps: increase non-alias ID range by reducing the alias space ID 2021-01-18 09:33:14 +01:00
TSC21 54486b995e uorb_rtps_message_ids: add required topics to enable offboard control from DDS 2021-01-18 09:33:14 +01:00
RomanBapst b1e442b830 vehicle_local_position: added bitfield for terrain estimate sensor info
- indicate how the distance to the bottom is estimated as this is important
to know in the context

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-01-17 12:06:59 +01:00
Beat Küng ade3871bee adc: add support for multiple sensor voltage channels 2021-01-15 10:57:20 -05:00
Beat Küng e2337a34eb system_power: add comp_5v_valid and can1_gps1_5v_valid
And fill it in from the v5x GPIO expander.
2021-01-15 10:57:20 -05:00
RomanBapst 447e14906c TECS: log more TECS states to enable better analysis
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-01-13 21:21:07 +03:00
Daniel Agar 48f125f150 estimated IMU bias preflight checks
- commander preflightcheck use estimator_sensor_bias message instead of EKF state index magic number
 - ekf2 publish estimated bias limits in estimator_sensor_bias
 - preflightcheck only error if bias estimate exceeds half of configured limit (delete COM_ARM_EKF_AB and COM_ARM_EKF_GB parameters)
2021-01-12 09:09:42 +01:00
TSC21 7c95e99156 tools: make sure that uORB type names found as part of field names are not capitalized as ROS types 2021-01-12 09:05:59 +01:00
Daniel Agar abec2bd8df
msg: estimator_status_flags shorten fields
- previously this message exceeded the logger total field length (1500 bytes)
2021-01-11 11:49:51 -05:00
TSC21 06b733bb86 msg: rtps: improve verbosity when the the client is not capable of parsing a specific ID 2021-01-10 22:22:22 +01:00
TSC21 3f1c303b16 msg: rtps: improve verbosity when the the agent is not capable of parsing a specific ID 2021-01-10 22:22:22 +01:00
Daniel Agar c6af260a41 log_message increase queue depth 2->4 2021-01-09 11:04:32 -05:00
Daniel Agar 88f8da27ef
save learned mag bias per sensor (Multi-EKF support)
- handle saving the mag bias per sensor (across all estimator instances using that mag) in sensors/vehicle_magnetometer
 - this is now saving back to the actual mag calibration CAL_MAGn_OFF{X,Y,Z}
 - ekf2 reset mag mag bias on any magnetometer or calibration change
 - use Kalman filter scheme to update stored mag bias parameters using all available bias estimates for that sensor

Co-authored-by: Paul Riseborough <gncsolns@gmail.com>
2021-01-07 09:54:13 -05:00
Matthias Grob e92795b474 Temporary logging addition to debug CI 2020-12-30 10:25:08 -05:00
Matthias Grob fafbb687d8 FlightModeManager: fix integral reset on ground
This information could also be used for yaw and integral
resets of the lower level controllers.
2020-12-30 10:25:08 -05:00
Matthias Grob 8329208b84 FlightModeManager: fix takeoff ramp from zero 2020-12-30 10:25:08 -05:00
Daniel Agar 4f62355dec
msg: new estimator_status_flags message for more accessible ekf2 status logging
- log all estimator (ekf2) flags as separate booleans in a new dedicated low rate message (only publishes at 1 Hz or immediately on any change)
 - this is a bit verbose, but it avoids the duplicate bit definitions we currently have across PX4 msgs, ecl analysis script, flight review, and many other custom tools and it's much easier for casual log review in FlightPlot, PlotJuggler, csv, etc
 - for compatibility I've left estimator_status filter_fault_flags, innovation_check_flags, and solution_status_flags in place, but they can gradually be removed as tooling is updated

Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
2020-12-29 11:27:21 -05:00
bazooka joe 8d5813994f format smart battery serial number as string on mavlink
according to change on mavlink protocol message
formatted as 'dd/mm/yy-123456'
2020-12-28 11:04:54 +01:00
Daniel Agar 7038cb8518 sensors: angular_velocity always get gyro rate from vehicle_imu_status
- sensor rate is used for control data low pass and notch filters
2020-12-16 10:12:27 -05:00
Daniel Agar 336176b2f0 Mavlink FLIGHT_INFORMATION fix arming time (ms -> us) and add takeoff time
- fixes https://github.com/PX4/PX4-Autopilot/issues/16393
2020-12-16 09:38:05 -05:00
Robin Lilja aa244a098c
Clarification of coordinate systems for sensors_* and vehicle_* messages (#16339)
Changed all 'NED' references to 'FRD'. Also cleaned up mixing of m/s/s and m/s^2 to use the latter. Corrected m/s/s to Pascals. Plus minor typos. Also made some minor cosmetic clean ups.

Co-authored-by: Robin <robin@Robins-MacBook-Pro-Work.local>
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
2020-12-15 09:18:05 +01:00
Daniel Agar ef6209ba03
new manual_control_switches msg (split out of manual_control_setpoint) (#16270)
- split out switches from manual_control_setpoint into new message manual_control_switches
 - manual_control_switches published at minimal rate (~ 1 Hz) or immediately on change
 - simple switch debounce in rc_update (2 consecutive identical decodes required)
 - manual_control_switches logged at full rate rather than sampled at (5-10% of messages logged)
 - manual_control_setpoint publish at minimal rate unless changing
 - commander handle landing gear switch for manual modes
 - processing of mode_slot and mode_switch is now split so we only do one or the other (not both)
     - a future step will be to finally drop mode_switch and accompanying switches entirely

Co-authored-by: Matthias Grob <maetugr@gmail.com>
2020-12-11 12:11:35 -05:00
Daniel Agar d44e537084
ekf2: update to new ecl to fix fault status getter
- estimator_status filter_fault_flags was broken because the union within ecl/EKF has exceeded 16 bits
2020-12-10 12:45:41 -05:00
Igor Campos c316af6ec7 update to match new feature as a new mavlink command Oblique Survey 260 2020-12-09 17:54:53 +01:00
Silvan Fuhrer 59564af860 wind_estimate message: add identifier for source
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2020-12-08 11:43:27 -05:00
Roman Dvořák bc1c8fb73a
GPS_DUMP_COMM: dump all gps instances 2020-12-08 11:45:24 +01:00
bresch f3e5b86b06 Commander: set home position in air
en/dis-able in-air home position via parameter COM_HOME_IN_AIR
2020-12-07 10:24:23 -05:00
TSC21 1d1fbdb1d3 microRTPS: remove byte ordering for nested types 2020-11-28 21:26:50 +01:00
Jukka Laitinen fdb4ede6c2 Add topic namespace support for micrortps agent generation
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2020-11-26 12:34:56 +00:00
Daniel Agar ed8a30d73e mavlink: STATUSTEXT directly use mavlink_log subscription
- ORB_ID(mavlink_log) increase queue depth now that mavlink ringbuffer is gone
2020-11-17 19:47:06 -05:00
Daniel Agar 5d7ea62190 estimator_innovations: remove unimplemented fake vel & pos fields
- easy to readd if and when they're needed
2020-11-11 20:17:52 -05:00
Daniel Agar d14deb0e5a FFT add simple median filter 2020-11-02 12:58:46 -05:00
TSC21 b1dc1b1ecd msg: rtps: add IDs for missing estimator_* msgs 2020-10-28 11:58:35 +01:00
TSC21 5b7d1a0496 msg: rtps: add missing ID for orb_test_medium_wrap_around 2020-10-28 10:18:22 +01:00
Daniel Agar df2f26ebdf
rename vehicle_visual_odometry_aligned -> estimator_visual_odometry_aligned
- saves a small amount of work for the ekf2 selector in multi-EKF mode (visual_odometry_aligned now ignored)
 - helps to distinguish the origin/purpose from vehicle_odometry and vehicle_visual_odometry
2020-10-27 12:33:39 -04:00
Daniel Agar 0f411d6820
Multi-EKF support (ekf2)
- ekf2 can now run in multi-instance mode (currently up to 9 instances)
    - in multi mode all estimates are published to alternate topics (eg estimator_attitude instead of vehicle_attitude)
 - new ekf2 selector runs in multi-instance mode to monitor and compare all instances, selecting a primary (eg N x estimator_attitude => vehicle_attitude)
 - sensors module accel & gyro inconsistency checks are now relative to the mean of all instances, rather than the current primary (when active ekf2 selector is responsible for choosing primary accel & gyro)
 - existing consumers of estimator_status must check estimator_selector_status to select current primary instance status
 - ekf2 single instance mode is still fully supported and the default

Co-authored-by: Paul Riseborough <gncsolns@gmail.com>
2020-10-27 10:56:11 -04:00
bresch 09cc3120e2 OpticalFlow: add optical flow velocity logging
This is important to align the flow with the IMU data and verify that
the compensation is properly done
2020-10-26 14:10:25 -04:00
Daniel Agar 614a0ac2a2
experimental/gyro_fft: improve peak detection, add start parameter
- add new parameter `IMU_GYRO_FFT_EN` to start
 - add 75% overlap in buffer to increase FFT update rate
 - space out FFT calls (no more than 1 per cycle)
 - increase `IMU_GYRO_FFT_MIN` default
 - decrease main stack usage
2020-10-25 23:48:21 -04:00
Daniel Agar 945c17bc3f
move subsystem_info entirely into commander and remove from uORB
* HealthFlags: define bitfield using 1<<X

Co-authored-by: Matthias Grob <maetugr@gmail.com>
2020-10-25 10:08:15 -04:00
Daniel Agar 0b74076265 msg: only include orb_test messages if PX4_TESTING enabled 2020-10-20 15:17:09 -04:00
Daniel Agar 1eb3c59277 systemcmds/topic_listener: use msg_files list from msg/ 2020-10-20 11:05:47 -04:00
Daniel Agar 16119f0e8c mavlink debug messages disable on CONSTRAINED_FLASH boards
- mavlink messages DEBUG/DEBUG_FLOAT_ARRAY/DEBUG_VECT/NAMED_VALUE_FLOAT move to separate stream headers and don't include if CONSTRAINED_FLASH
 - mavlink receiver DEBUG/DEBUG_FLOAT_ARRAY/DEBUG_VECT/NAMED_VALUE_FLOAT handling excluded if CONSTRAINED_FLASH
 - msg: skip debug_array.msg, debug_key_value.msg, debug_value.msg, debug_vect.msg if CONSTRAINED_FLASH
2020-10-20 11:05:47 -04:00
FengShun d19b54481a fix: uORB topics lost messages when publications overflow 2020-10-19 08:52:55 +02:00
mcsauder 047531b924 Add MavlinkStreamGPSStatus status class stream via GPS_STATUS.hpp and add PRN code to satellite_info.msg. 2020-10-14 08:26:42 +02:00
Daniel Agar 8d1b99be31
mavlink: telemetry status only log simple HEARTBEAT validity
* delete telemetry_heartbeat msg
 * delete unused _telemetry_status_mutex
2020-10-13 13:37:10 -04:00
Daniel Agar d71ca37087
navigator: publish navigator mission item changes for logging
- new msg navigator_mission_item for inspecting navigator mission item processing
2020-10-13 12:12:03 -04:00
Daniel Agar f557fa46e8
gyro_fft improve peak finding, parameterize min/max frequencies, remove debug logging
- add min/max frequency parameters for peak detection (IMU_GYRO_FFT_MIN, IMU_GYRO_FFT_MAX)
 - remove full FFT debug logging
 - fix Quinn's second estimator
 - log sensor_gyro_fft
 - fake_gyro use PX4Gyroscope
2020-10-12 15:19:39 -04:00
Daniel Agar eecf2e7a1e
sensors: allow up to 4 accels, gyros, and baros and add configurable rotations for accel & gyro 2020-10-08 19:01:44 -04:00
Daniel Agar c01fabaf11
FW move altitude first order hold (FOH) and loiter to position special cases from navigator to position controller
Co-authored-by: RomanBapst <bapstroman@gmail.com>
2020-10-06 16:57:12 -04:00
Silvan Fuhrer 5a184d2f5c Commenting and formating fixes
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2020-10-06 09:31:58 +02:00
Silvan Fuhrer 8f858d95e6 Rename equivalent airspeed (EAS) to calibrated airspeed (CAS)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2020-10-06 09:31:58 +02:00
Daniel Agar f01c4e769f
sensors/vehicle_imu: vehicle_imu_status add mean accel/gyro
- this makes it slightly easier to gather long term data for an Allan Variance
 - fixes https://github.com/PX4/Firmware/issues/6250
2020-10-05 22:18:03 -04:00
Daniel Agar 08bf71b73d
drivers/tone_alarm and tune_control small improvements/cleanup
- drivers/tone_alarm: move to ModuleBase and purge CDev (/dev/tone_alarm0)
 - drivers/tone_alarm: only run on tune_control publication (or scheduled note) rather than continuously
 - drivers/tone_alarm: use HRT to schedule tone stop (prevents potential disruption)
 - msg/tune_control: add tune_id numbering
 - systemcmds/tune_control: add "error" special case tune_id
 - move all tune_control publication to new uORB::PublicationQueued<>
 - start tone_alarm immediately after board defaults are loaded to fix potential startup issues
 - for SITL (or other boards with no TONE output) print common messages (startup, error, etc)
2020-10-05 21:39:26 -04:00
Daniel Agar 8ee0c62e57
examples: add Gyro FFT using CMSIS 5 on Cortex-m (#15104)
- this is a work in progress experiment to compute real time FFTs from raw gyro FIFO data on Cortex-m hardware (stm32f4/f7/h7, etc)
2020-10-02 11:47:27 -04:00
Daniel Agar cf26f24387
msg: add quaternion euler angle pretty print 2020-09-28 10:13:43 -04:00
Jacob Dahl a24488328f
Move GPS blending from ekf2 to sensors module
- new sensors work item that subscribes to N x sensor_gps and publishes vehicle_gps_position
 - blending is now configurable with SENS_GPS_MASK and SENS_GPS_TAU

Co-authored-by: Jacob Crabill <jacob@volans-i.com>
Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
2020-09-25 23:28:31 -04:00
Daniel Agar 861e06dfd7
mavlink: handle receiving GENERATOR_STATUS
- only published (ORB_ID(generator_status)) and logged for now
2020-09-25 11:36:58 -04:00
Daniel Agar 0dc8bb9c86
uORB: increase ORB_MULTI_MAX_INSTANCES 4 -> 10
- put more realistic bounds on maximum number of battery instances, gps, etc
2020-09-24 11:01:28 -04:00
Julian Oes 53b14233a2 mavlink: handle failure injection commands
This adds handling of MAVLink failure injection commands. An
additional parameter is added as a guard to prevent triggering any
failures by accident.
2020-09-16 12:51:56 -04:00
Daniel Agar c41f053c7b
vehicle_imu/vehicle_magnetometer add calibration indicator to message
- vehicle_imu/vehicle_magnetometer add monotonically increasing `calibration_count` field so that downstream subscribers are aware of calibration changes
2020-09-15 13:12:57 -04:00
Daniel Agar 60d613ea04
sensors: sensor_preflight_imu -> sensors_status_imu and run continuously
- inconsistency checks now run continuously instead of only preflight
 - keep inconsistencies for all sensors
 - add per sensor data validator state as overall health flag
2020-09-06 22:06:13 -04:00
Daniel Agar ca9b6bc137
commander: quick mag cal with fixed heading use MAV_CMD_FIXED_MAG_CAL_YAW message
- use proper Mavlink MAV_CMD_FIXED_MAG_CAL_YAW command for initiating magnetometer quick cal
 - MAV_CMD_FIXED_MAG_CAL_YAW allows specifying the yaw and optionally latitude and longitude if the vehicle doesn't have GPS
2020-09-06 19:25:11 -04:00
Daniel Agar dfa82b58fd msg/tools/uorb_to_ros_msgs.py set executable 2020-09-06 23:31:52 +02:00
Daniel Agar e5879f1bb6 estimator_sensor_bias: add bias variance 2020-09-04 10:48:26 -04:00
Daniel Agar c54a0ff0c7 estimator_status: add device ids for accel/baro/gyro/mag 2020-09-04 10:48:26 -04:00
Daniel Agar 20c2fe6d28 estimator messages add explicit timestamp_sample
- timestamp is uORB publication metadata
 - this allows us to see what the system saw at publication time plus the latency in estimation
2020-09-04 10:48:26 -04:00
Daniel Agar 09666c324f msg: add mag device id pretty print decode 2020-09-04 10:48:26 -04:00
Daniel Agar 9ccc1db649 estimator_status split out estimator_states 2020-09-04 10:48:26 -04:00
TSC21 98f53c2bc4 microRTPS: extend verbose arg to the timesync 2020-08-28 09:22:36 +02:00
TSC21 d09cb8d1f0 microRTPS: reduce the number of streams on the bus 2020-08-28 09:22:36 +02:00
TSC21 603a4d8955 microRTPS: transport: fix parsing 2020-08-28 09:22:36 +02:00
Daniel Agar f2c9865c9b sensor mag add minimal queue and calibration check all
- mag calibration acceptance check sphere/ellipsoid fit status
2020-08-21 10:12:13 -04:00
Daniel Agar 971b1e4b4d sensors: move mag aggregation to new VehicleMagnetometer WorkItem
- purge all reminaing magnetometer IOCTL usage
 - mag calibration add off diagonal (soft iron) scale factors
2020-08-21 10:12:13 -04:00
bazooka joe 190b96a46c SMbus battery driver - a lot of updates and optimizations
- added support for BQ40Z80 based battery
- added performance counter for interface errors
- added SMART_BATTERY_INFO mavlink message
- general code cleanups and optimization
- fixed: void flooding the log in case of interface error
- fixed: using _batt_startup_capacity instead of _batt_capacity for discharged_mah
- update: read manufacture_date
- update: get _cell_count from parameter and not const 4
- update: avoid re-reading data that has already been read and stored on class already
- currently the battery type defined by BAT_SMBUS_MODEL parameter and not by auto detection
2020-08-18 21:41:19 -04:00
TSC21 a091a70470 microRTPS: split the microRTPS client and agent dest directories for better visbility and handling 2020-08-18 17:16:04 +02:00
Daniel Agar 97fc1db768 vehicle_local_position: rename yaw -> heading and add reset logic
- vehicle_global_position yaw removed (redundant)
2020-08-10 11:42:03 +02:00
Daniel Leonard Robinson fa4818e467
vehicles: add new vehicle type: Airship (#14862)
Co-authored-by: Anton Erasmus <anton@flycloudline.com>
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
2020-08-10 08:52:51 +02:00
Daniel Agar 3002e74b4f
mavlink: publish telemetry_status per instance with all HEARTBEATS from the same system
- one telemetry_status publication per mavlink instance
 - each telemetry_status has an array of HEARTBEATS
2020-08-07 12:23:52 -04:00
Beat Küng 5f8c6512b3 vehicle_status: add latest arming/disarming reason
Makes it easier to debug.
2020-08-04 10:53:20 -04:00
Daniel Agar ba640acfcc
mc_hover_thrust_estimator: validity flag and other small improvements/fixes
- track and publish validity based on hover thrust variance, innovation test ratio, and hysteresis
 - only publish on actual updates or becoming inactive
 - fix dt (previous timestamp wasn't being saved)
 - use local position timestamp (corresponding) to accel data rather than current time to avoid unnecessary timing jitter
 - check local position validity before using
 - mc_hover_thrust_estimator: move from wq:lp_default -> wq:nav_and_controllers to ensure the hover thrust estimator runs after the position controller and uses the same vehicle_local_position data
 - land_detector: check hover thrust estimate validity and adjust low throttle thresholds if hover thrust is available
 - mc_pos_control: only use hover thrust estimate if valid
2020-08-03 10:30:52 -04:00
Daniel Agar 63a23957b1
rc/dsm: decode improvements
- always check system field for validity
 - reject any data outside of "servo position" valid range from Spektrum specification
 - properly support XPlus channels (12+)
 - debug message if channel count changes
2020-08-02 12:52:16 -04:00
TSC21 342b1c5ded microRTPS: client: properly set task/thread naming 2020-07-31 14:13:10 +01:00
TSC21 162e0c7675 microRTPS: client: reserve the minimum required stack to the send/receive tasks 2020-07-31 14:13:10 +01:00
TSC21 0b41aa3ecd microRTPS: client: dynamically allocate the uORB pub/subs 2020-07-31 14:13:10 +01:00
TSC21 398f104918 microRTPS: transport: do not discard message from rx_buffer if a CRC error occurs 2020-07-31 14:13:10 +01:00
TSC21 1ab193f548 microRTPS: remove the need for the eClock util 2020-07-31 14:13:10 +01:00
TSC21 acc3866ac9 generate_microRTPS_bridge: make sure that the ROS2 version of FastRTPS is grabbed in a colcon build 2020-07-31 14:13:10 +01:00
TSC21 311a8144e1 microRTPS: client: use structs for pub/subs to avoid increasing the stack usage 2020-07-31 14:13:10 +01:00
TSC21 3db9307dfb microRTPS: transport: make seq_number non-atomic 2020-07-31 14:13:10 +01:00
TSC21 08e72b29b3 microRTPS: micrortps_timesync: reduce max RTTI to 50ms 2020-07-31 14:13:10 +01:00
TSC21 c01bcd41f7 microRTPS: minor adjustements so to improve the readings; add more baud rate options
Co-authored-by: Andrew Wedemier <andrew.wedemier@gmail.com>
2020-07-31 14:13:10 +01:00
TSC21 0124ca6e41 microRTPS: add debug verbose option '-v'; use while loop for reads; ease the RTTI check on timesync 2020-07-31 14:13:10 +01:00
TSC21 2f4eff4c38 microRTPS: add possibility to set HW or SW flow control; improve verbosity aesthetics 2020-07-31 14:13:10 +01:00
TSC21 b2845c60d3 microRTPS: move buffer size to transport 2020-07-31 14:13:10 +01:00
TSC21 407bd8860f microRTPS: transport: hotfix to skip data packets that that don't fit the buffer and continue the readings 2020-07-31 14:13:10 +01:00
TSC21 25d2236cce microRTPS: fix FastRTPS version check on agent templates 2020-07-31 14:13:10 +01:00
Daniel Agar 7b46efaa6b logger: record message gaps 2020-07-29 13:36:22 -04:00
stmoon 71b7647ca1 fix the return type problem of RTPS 2020-07-27 16:22:46 +01:00
stmoon b457122489 remove unnecessary stderr msg when checking ldconfig 2020-07-27 16:21:58 +01:00
Daniel Agar 81f57bccb6 px4io: servorail_status -> px4io_status and log all flags 2020-07-21 09:56:13 -04:00
Daniel Agar 459abcd035 uORB: print individual bits of fields
- applies to messages with names containing "flags" or "bits" and unsigned fixed width integer type (uint8, uint16, uint32)
2020-07-19 12:25:15 -04:00
Daniel Agar 1394b5d7bc sensor_baro add separate timestamp_sample field
- the timestamp is uORB message publication metadata
2020-07-17 09:42:19 -04:00
stmoon 4418179a92 fix the fastrtps version problem in case of v1.10.0 2020-07-15 16:30:58 +01:00
David Jablonski 589aff7e0d Orbit: Add RC controlled yaw mode
For the RC controlled yaw behaviour, we do a yaw setpoint according to
the stick expo. The uncontrolled yaw behaviour behaves undefined.
Switching between yaw behaviours makes the drone stand still for a
moment, which probably can be improved.
2020-07-13 20:26:13 +02:00
JaeyoungLim fa0ca7e65c Update mavlink with cellular status message fixes
This Commit includes a update of the mavlink submodule

since the CELLULAR_STATUS message was updated, the necessary changes were done together
Add enums
2020-07-09 15:12:02 -04:00
Thomas Stauber 6d1ce57362
Add Land as Geofence Action 2020-07-09 10:32:10 -04:00
Claudio Micheli 6358dd400a failure detector: added esc failures detection
Signed-off-by: Claudio Micheli <claudio@auterion.com>
2020-07-01 08:55:54 +02:00
TSC21 dc69d99764 add support to FastRTPS 2.0.0 (Fast-DDS) 2020-06-29 22:56:00 +02:00
Daniel Agar 22daa26955 msgs/sensor_mag: remove unused raw, add timestamp_asmple, shrink error count
- move mpu9250 sensitivity handling back to driver (this isn't common)
2020-06-22 10:11:22 -04:00
Daniel Agar f55ed0992c
accel and gyro calibration refactor and cleanup
- remove all remaining IOCTLs for accel and gyro and handle all calibration entirely in sensors module with parameters
 - sensor_accel and sensor_gyro are now always raw sensor data
 - calibration procedures no longer need to first clear existing values before starting
 - temperature calibration (TC) remove all scale (SCL) parameters
    - gyro and baro scale are completely unused
    - regular accel calibration scale can be used (CAL_ACC*_xSCALE) instead of TC scale
2020-06-17 22:50:09 -04:00
Daniel Agar e34bdb4be9
move IMU integration out of drivers to sensors hub to handle accel/gyro sync
- IMU integration move from drivers (PX4Accelerometer/PX4Gyroscope) to sensors/vehicle_imu 
 - sensors: voted_sensors_update now consumes vehicle_imu
 - delete sensor_accel_integrated, sensor_gyro_integrated
 - merge sensor_accel_status/sensor_gyro_status into vehicle_imu_status
 - sensors status output minor improvements (ordering, whitespace, show selected sensor device id and instance)
2020-05-30 11:07:54 -04:00
kritz 3897030c6f
Support odometry velocity in body and local frame (#14703)
* Update submodule ECL

* increase lower bound on EVV param
2020-05-13 12:43:02 +02:00
Daniel Agar c5cbc7725d msg: timestamp_sample print elapsed from timestamp 2020-05-11 12:58:52 -04:00
Mohammed Kabir 5ffe88672e vehicle_odometry: add timestamp_sample field for latency monitoring 2020-04-28 13:58:43 -04:00
Daniel Agar cf37be8c44
ekf2 handle accelerometer clipping
- track clipping per IMU axis and pass through to ecl/EKF
 - update ecl/EKF to include delta velocity clipping changes (PX4/ecl#663)
2020-04-07 20:11:08 -04:00
TSC21 4f718086ea microRTPS: fix topic name when ROS2 is not being used 2020-04-07 16:34:30 +01:00
Julian Oes cafd52647c msg: fix battery source enum 2020-04-06 15:56:54 +02:00
Julian Oes f650b91718 battery: check source param inside battery lib
This moves the handling of the BAT%d_SOURCE param inside of the battery
library. Users of the library now pass the source instead of the flag
whether to publish. The battery library then checks if the source is
selected using the param and publishes accordingly.

Since we removed the strange system_source flag, we now need to look at
all batteries in commander.
For current estimation - I think - it makes sense to sum them up.
2020-04-06 15:56:54 +02:00
Julian Oes 5beb293a6a msg: fix typo 2020-04-06 15:56:54 +02:00
stmoon 9a0c50325b remove exception in case that ROS is not installed 2020-04-04 08:20:35 +01:00
stmoon aaa72b2a25 change how to get ros2 version 2020-04-04 08:20:35 +01:00
TSC21 144c65c92f microRTPS: only use '-typeros2' FastRTPSGen option for Dashing and later ROS2 distros 2020-04-03 18:03:26 +01:00
Claudio Micheli dc29a994b7 msg: extend field definition in msg/esc_report (arming & failure states)
Signed-off-by: Claudio Micheli <claudio@auterion.com>
2020-04-03 09:16:43 +02:00
TSC21 2020b77a43 microRTPS: use FastRTPSGen '-typeros2' option to generate the typenaming required to interface the bridge with ROS2 topics 2020-04-02 14:28:38 +01:00
Julian Oes 07d172dc9c tools: present nicer error for missing packaging
This makes the error more user friendly and suggests what to do to fix
it.
2020-04-01 10:42:18 +01:00
Hyon Lim 3bcd8c63f8
SMBus battery (a.k.a. smart battery) enhancement. (#14496)
* Enhancement: State of health, and max_error value is added. Both shows battery health of SMBUS smart battery.
 * Enhancement: BAT_C_MULT parameter is introduced. This is for high-current capable SMBUS-based battery.
As SMBUS only provides 16-bit for current, it could only be +-32768mA which is about +-32A.
But with proper treatment, it could be extended with little accuracy loss.
This factor can be set for individual battery system with available information.
    * Relative SOC introduced. Proper SMBUS battery should provide percentage of remaining battery
directly. Therefore it does not have to be computed like before.
    * State of Health introduced. Proper SMBUS battery should provide SOH value.
    * Max error: this shows estimation error of BMS.
 * Enhancement: With smart battery, precise estimation of time remaining is provided
with impedance track. It is unit of minute, so 60 seconds multiplied.
Update rate of this is not fast, but very useful.

Co-authored-by: Hyon Lim <lim@uvify.com>
2020-03-31 17:28:22 -04:00
Daniel Agar 2b82b471c1 sensor_accel_fifo increase to 32 samples 2020-03-31 13:26:50 -04:00
David Jablonski a0bf7425ae Implemented multipart status message 2020-03-31 09:23:52 +02:00
Timothy Scott 14a61a6695 Fixed reporting of battery voltages in uORB 2020-03-31 09:14:50 +02:00
Roman Dvořák b02e209507
Remove duplicite data from RPM message and enable logging of RPM message 2020-03-30 13:08:53 -04:00
David Jablonski 536cd6cb1a allow DO_CONTROL_VIDEO in missions 2020-03-30 17:10:36 +02:00
David Jablonski 6bd191a24e Mavlink: Implemented SET_CAMERA_ZOOM 2020-03-30 17:10:36 +02:00
TSC21 c4f8f39ca9 microRTPS: templates: use full version comparison when checking for version 1.7 2020-03-24 17:47:39 +00:00
TSC21 1b453ed849 microRTPS: templates: check only the major and minor of FastRTPS to set the 'discovery_config' namespace 2020-03-24 16:43:12 +00:00
TSC21 1ea5280299 microRTPS: use package.version to compare FastRTPS lib versions 2020-03-24 13:31:41 +00:00
SalimTerryLi dc8e775d8f
ADC: replace ioctl with uorb message (#14087) 2020-03-20 11:23:32 +01:00
Lorenz Meier ed0a01d5da Commander: Add reporting of preflight and prearming state
This is essential for the operator to know if the system is ready to fly.
2020-03-17 00:17:11 +01:00
Paul Riseborough ab92b46e69
Update ecl to add ability to recover from bad magnetic yaw
* msg: Add EKF-GSF yaw estimator logging data
* ecl: update to version with EKF-GSF yaw estimator
* ekf2: Add param control and logging for EKF-GSF yaw estimator
* logger: Add logging for EKF-GSF yaw esimtator
2020-03-15 12:57:25 -04:00
Lorenz Meier cb63fcdcc4 Vehicle command: Add mission item to gate mission execution on line orthogonal to current trajectory 2020-03-14 17:50:40 +01:00
Daniel Agar 0eca583ecf sensors: move baro aggregation to new sensors/vehicle_air_data 2020-03-12 19:06:34 -04:00
TSC21 69b38c9ced RTPS: add IDs to 'orb_test' related multitopics 2020-03-12 11:10:50 +00:00
Daniel Agar a89b69b0ea
vehicle_global_position: remove velocity fields (duplicates of local vx, vy, vz)
* attitude_estimator_q: get velocity from local position (if available)
2020-03-11 23:57:43 -04:00
Daniel Agar 5d33b9e999
delete Outback Challenge (OBC) AUTO_RTGS (datalink loss) and AUTO_RCRECOVER (rc loss) 2020-03-11 22:45:55 -04:00
TSC21 2b8eb736e1 microRTPS: timesync: fix comment indentation 2020-03-11 15:13:07 +00:00
TSC21 21f0d99145 microRTPS: RtpsTopics: code specialization simplification 2020-03-11 15:13:07 +00:00
TSC21 e9bc675bfa microRTPS: agent: simplify Publisher code specialization 2020-03-11 15:13:07 +00:00
TSC21 296714a00a microRTPS: agent: simplify Subscriber code specialization 2020-03-11 15:13:07 +00:00
TSC21 99f96437c3 microRTPS: timesync: add getters and setter to generalize interface 2020-03-11 15:13:07 +00:00
TSC21 7612879ffd microRTPS: use FastRTPS version instead of FastRTPSGen version to generate conditional code 2020-03-11 15:13:07 +00:00
TSC21 c7d86b73d4 microRTPS: RtpsTopics: generalize types and member functions access 2020-03-11 15:13:07 +00:00
Daniel Agar 9585055e9e
uORB: add bitset for faster orb_exists check and remove uORB::Subscription lazy subscribe hack/optimization
- add PX4 bitset and atomic_bitset with testing
 - add uORB::Subscription constructor to take ORB_ID enum
 - move orb test messages into msg/
2020-03-11 09:06:33 -04:00
TSC21 04ec2041e3 microRTPS: timesync: cleanup and style fix 2020-03-10 12:15:18 +00:00
TSC21 512c405834 microRTPS_timesync.h: fix comments notation so to be properly generated in EmPy 2020-03-10 12:15:18 +00:00
TSC21 1893c9e37e microRTPS_timesync.h: add description to functions 2020-03-10 12:15:18 +00:00
TSC21 a3487ab8a3 microRTPS: timesync: fix unit conversion 2020-03-10 12:15:18 +00:00
TSC21 59869b2350 microRTPS_timesync.cpp: fix style 2020-03-10 12:15:18 +00:00
TSC21 7de8bee29e microRTPS: timesync: interpolate 2020-03-10 12:15:18 +00:00
TSC21 2568d9ae20 mavlink: timesync: readd timesync_status uORB to report Mavlink timesync 2020-03-10 12:15:18 +00:00
TSC21 250b6b24ab microRTPS: timesync: properly apply offsets 2020-03-10 12:15:18 +00:00
TSC21 67491b473c microRTPS: add timesync handshake 2020-03-10 12:15:18 +00:00
TSC21 e3e607f600 microRTPS: client: add client response to timesync 2020-03-10 12:15:18 +00:00
TSC21 2ec8958351 microRTPS: microRTPS_timesync: fix template indentation 2020-03-10 12:15:18 +00:00
TSC21 6dea2dd97d microRTPS: agent: make sure that is able to subscribe a timesync stream from itself 2020-03-10 12:15:18 +00:00
TSC21 cfd8e368df microRTPS: timesync: template generalization for both ROS2 and non-ROS2 2020-03-10 12:15:18 +00:00
TSC21 01518bd009 microRTPS: delete run() functions as they are not needed 2020-03-10 12:15:18 +00:00
TSC21 db7d98c16f microRTPS: use char-by-char comparison instead of stringstream comparison 2020-03-10 12:15:18 +00:00
TSC21 80c658c1ae microRTPS: make sure that Sub/Pubs do not exchange data in loop (i.e. for the same entity) 2020-03-10 12:15:18 +00:00
TSC21 441e6290eb microRTPS: timesync: apply offset atomically 2020-03-10 12:15:18 +00:00
TSC21 170835f3f8 microRTPS: add timesync for the agent side 2020-03-10 12:15:18 +00:00
Julian Kent eab88294f8 Add documenation to uORB message 2020-03-09 09:51:49 +01:00
Julian Kent 6e1185d4f2 Add uORB messages for bezier curve trajectories 2020-03-09 09:51:49 +01:00
Julian Oes 874c6f385b commander: unify offboard timeouts
The implementation before this change had two timeouts, a hard-coded
timeout of 0.5 seconds as well as a by param configurable timeout with
certain failsafe actions set.

This change aims to fix two problems:
1. The hard-coded offboard timeout can be triggered easily with sped up
   lockstep simulation. Since i t is hard-coded it can't be adapted to
   the speed factor.
2. The offboard signal can time out but no action will be taken just
   yet. This means we end up in an in-between stage where no warning or
   failsafe action has happened yet, even though certain flags are set
   to a timeout state.

This patch aims to fix this by unifying the two timeouts to the existing
configurable param. The convoluted double timeout logic is replaced by a
simple hysteresis.

For anyone that has previously not changed the default timeout param (0),
the param will now be changed to 0.5 seconds which reflects the
previously hardcoded time. For anyone with a specific timeout
configured, the behaviour should remain the same.

Also, going forward, timeouts lower than 0.5 seconds should be possible.
2020-03-04 09:35:14 +01:00
Martina Rivizzigno aee1e70642 check avoidance status in commander and set sys status
remove mavlink log
2020-03-02 16:49:56 +01:00
Matthias Grob f90d3671c0 vehicle_attitude_setpoint: get rid of unused q_d_valid flag 2020-02-27 09:17:52 +01:00
Daniel Agar 22499effb9 invensense icm20602 improvements
- checked register mechanism and simple watchdog
    - driver checks for errors gradually and can reconfigure itself
 - respect IMU_GYRO_RATEMAX at the driver level
 - fixed sensor INT16_MIN and INT16_MAX handling (y & z axis are flipped before publishing)
 - increased sensor_gyro_fifo max size (enables running the driver much slower, but still transferring all raw data)
 - PX4Accelerometer/PX4Gyroscope remove unnecessary memsets
2020-02-18 19:21:20 -05:00
Julian Oes 9a96ca14be Tools: make Python import error more readable
The problem with printing the exception was that starting with
Python 3.6 the ImportError is yet another (sub) exception called
ModuleNotFoundError which can't be printed as a string and then triggers
another exception:

```
Traceback (most recent call last):
  File "/home/julianoes/src/Firmware/Tools/serial/generate_config.py", line 11, in <module>
    import jinja2
ModuleNotFoundError: No module named 'jinja2'

During handling of the above exception, another exception occurred:

Traceback (most recent call last):
  File "/home/julianoes/src/Firmware/Tools/serial/generate_config.py", line 13, in <module>
    print("Failed to import jinja2: " + e)
TypeError: must be str, not ModuleNotFoundError
```

As per @bkueng's suggestion the easiest is to cast the exception to str
and that way prevent the second exception.
2020-02-14 11:40:05 +01:00
stmoon 8b273b46aa fix the encoding problem for subprocess.check_output 2020-02-09 10:12:15 +00:00
bresch ca0b5700ab uorb_rtps_message_ids: add hover_thrust_estimate msg 2020-02-07 11:52:52 +01:00
bresch 0f1c7590e9 HoverThrustEstimator: add a new single state estimator
with measurement noise auto-tuning

The purpose of this estimator is to improve land detection and vertical
velocity feedforward

Recovery strategy:
This is required when the setpoint suddenly changes in air or that the
EKF is diverging. A lowpassed test ratio is used as a trigger for the recovery logic
Also, a lowpassed residual is used to estimate the steady-state value
and remove it when estimating the accel noise to avoid increasing the
accel noise when the redisual is caused by an offset.
2020-02-07 11:52:52 +01:00
CarlOlsson a61f1647ad replay: remove GPS relative timestamps
Signed-off-by: CarlOlsson <carlolsson.co@gmail.com>
2020-02-07 08:19:22 +01:00
Nico van Duijn 7778cbd463
Mavlink: Add MAV_x_RADIO_CTL parameter to disable RADIO_STATUS flow control
* Add param for software flow ctl on 3DR radios
* Dont reset telemetry type on radio timeout
* Treat 3DR radio as generic link type
* Rename 3DR to SiK radio
2020-02-03 09:49:47 -05:00
Roman Dvořák c8a58c5c9d
drivers: add PCF8583 RPM sensor (#14018) 2020-02-02 12:10:20 -05:00
Daniel Agar 931a3f2684
logger: publish initial logger_status orb message 2020-01-29 17:29:30 -05:00
Daniel Agar 2410b31662
sensors: move accel filtering to sensors/vehicle_acceleration
I've added a queue depth of 4 for sensor_accel and sensor_gyro. This is initially added because it's not always possible for the `vehicle_acceleration` to keep up with every publication of the primary accelerator as it runs in the same thread as ekf2, various controllers, etc. 

Later this mechanism will be used in a few areas
 - rate limit `vehicle_angular_velocity` and `vehicle_acceleration` without missing any raw data
 - move IMU integration to `vehicle_imu` and out of the actual driver threads, eliminating the need for sensor_accel_integrated and sensor_gyro_integrated
 - integrate raw gyro synchronized with optical flow measurements
2020-01-29 16:13:38 -05:00
Silvan Fuhrer 4fa64f686a pre arm check: add circuit breaker for the VTOL arming in fixed-wing mode prevention
Added a new circuit breaker that, if set, enables arming in fixed-wing mode for VTOLs.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2020-01-28 00:30:24 +01:00
Daniel Agar 1237402fa4
sensors: compute and publish vehicle_angular_acceleration
- introduces parameter IMU_DGYRO_CUTOFF to configure the angular acceleration low pass filter
 - the angular acceleration is computed by differentiating angular velocity after the notch filter (IMU_GYRO_NF_FREQ & IMU_GYRO_NF_BW) is applied

Co-authored-by: Julien Lecoeur <jlecoeur@users.noreply.github.com>
2020-01-27 16:44:01 -05:00
Daniel Agar 24f0c2d72a
sensors: move gyro filtering to sensors/vehicle_angular_velocity
- gyro filtering (low-pass and notch) only performed on primary gyro in `sensors/vehicle_angular_velocity` instead of every gyro in `PX4Gyroscope`
 - sample rate is calculated from actual updates (the fixed value was slightly wrong in many cases, and very wrong in a few)
 - In the FIFO case the array is now averaged and published in `sensor_gyro` for filtering downstream. I'll update this in the future to use the full FIFO array (if available), but right now it should be fine.
2020-01-27 10:05:33 -05:00
Daniel Agar 10410fc868 msg: rename sensor_bias -> estimator_sensor_bias 2020-01-27 09:03:27 +01:00
Beat Küng d68e595514 vehicle_control_mode: fix invalid comment for flag_armed 2020-01-24 08:42:16 +01:00
Daniel Agar 697dbfb9f8 sensors/vehicle_imu: incremental step towards multi-EKF 2020-01-22 18:04:29 -05:00
Tal Zaitsev 65aaf5170c microRTPS: Fix C++11 remnant 2020-01-22 00:30:47 -05:00
Daniel Agar b47eaa6061
update C++ standard (c++11 -> c++14)
- temporarily disable snapdragon builds until toolchain is updated
2020-01-21 21:49:10 -05:00
Daniel Agar dc05ceaad2
create temperature_compensation module
- this is a new module for temperature compensation that consolidates the functionality previously handled in the sensors module (calculating runtime thermal corrections) and the events module (online thermal calibration)
 - by collecting this functionality into a single module we can optionally disable it on systems where it's not used and save some flash (if disabled at build time) or memory (disabled at run time)
2020-01-20 21:42:42 -05:00
stmoon 44cac04abe fix the bug for none of recv_topics 2020-01-20 12:33:47 +00:00
Daniel Agar c270e75156
vehicle_local_position: delete unused and redundant dist_bottom_rate 2020-01-18 12:50:57 -05:00
Daniel Agar bb465ca5b7
sensor accel/gyro message cleanup
- split out integrated data into new standalone messages (sensor_accel_integrated and sensor_gyro_integrated)
 - publish sensor_gyro at full rate and remove sensor_gyro_control
 - limit sensor status publications to 10 Hz
 - remove unused accel/gyro raw ADC fields
 - add device IDs to sensor_bias and sensor_correction
    - vehicle_angular_velocity/vehicle_acceleration: check device ids before using bias and corrections
2020-01-18 01:15:00 -05:00
Daniel Agar 1d932f6ec9
IMU drivers using FIFOs increase max length to 16 and sync similar implementations
- this provides some extra space when the FIFO transfers don't align perfectly
 - I've also made an effort to keep the different drivers (icm20602, icm20608g, ism330ldc) in sync so we can factor out the common portions later once we've confident in the pattern.
2020-01-17 22:06:09 -05:00
Low Orbit Ion Cannon 7dd949edb1 ADSB traffic avoidance improvements using UTM_GLOBAL_POSITION (#13159)
* Treat UAVS diffrently from manned aviation 
 * Added fake_traffic testing functionality,
 * Added NAV_TRAFF_AVOID Hold and Landmode
 * Added Behavior: HOLD Position to collision avoidance mode and implemented Landmode to collision avoidance.

Boards where no Hardware GUID is defined will send 0 as GUID.

Right now collision avoidance for more than one FMU without Hardware GUID is not possible.
We should consider adding a randomly generated HW GUID as a placeholder for legacy Boards
2020-01-17 14:58:28 -05:00
TSC21 1cbb3ebd4f microRTPS bridge: clean build warnings; improve verbosity 2020-01-17 12:19:00 +00:00
Julian Oes e98fa891fe msg/tools: remove unused import, check for six 2020-01-16 16:25:26 +01:00
Julian Oes 0a2b42b25d msg/tools: improve Python dependency note
We now check individually for empy and genmsg.

Also, my recommendation is to use pip3 as a user to install the
dependencies as this is least intrusive and should work on all
platforms.
2020-01-16 16:25:26 +01:00
TSC21 d6cff809f3 uorb_rtps_message_ids.yaml: onboard_computer_status to be received 2020-01-15 19:40:09 +00:00
TSC21 0cb1b250e9 px_generate_uorb_topic_files.py: update import error recommendation message 2020-01-13 21:48:35 +00:00
TSC21 2be7ca08ba msg: generation and parsing scripts: add Python3 support 2020-01-13 21:48:35 +00:00
Julian Oes 4329de9e3b Use Python 3 everywhere
Since Python 2 is retired in 4 months, we should move everything to 3.
2020-01-13 21:48:35 +00:00
TSC21 2e9a4d89ee msg: remove gencpp and genmsh submodules; remove gencpp imports 2020-01-13 21:48:35 +00:00
stmoon e19e0bd616 serach and insert rtps path if there is no {FASTRTPSGEN_DIR} 2020-01-10 16:48:21 +00:00
TSC21 722f287281 msg: urtps: change the topic Data Type name to match expected on ROS2 2020-01-10 13:42:36 +01:00
kamilritz e95e5abdf6 Update ECL 2020-01-09 10:36:10 +01:00
kamilritz 593895293a Transform vision covariances 2020-01-09 10:36:10 +01:00
Daniel Agar 253296eec7 vehicle_status_flags: remove unused circuit_breaker_engaged_gpsfailure_check 2020-01-08 12:29:50 -05:00
Jacob Dahl d08ec05bab PWM automatic trigger system (ATS) for parachutes (#13726)
* parameter and logic to commander for triggering failsafe from external automatic trigger system.
* logic to startup script for enabling ATS. Added uORB publishing to pwm_input module.
* Refactored out CDev usage from pwm_input and ll40ls. Refactored out ll40ls specifics from pwm_input and cleaned up dead code.
2020-01-06 20:14:06 -05:00
Daniel Agar f7cf1ffc41 drivers/uavcan: remove MAVLINK header dependency 2019-12-31 21:01:21 -05:00
Silvan Fuhrer 574b482fdb Navigator: make weather vane work in all auto modes, not just mission (#13761)
- rename of flag in position sp: from allow_weather_vane to disable_weather_vane
 - flag now doesn't have to be set for all auto modes, meaning that weather vane is also active outside of mission
 - flag is set before front transition to align with wp, and unset after alignment is over

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2019-12-28 12:13:15 -05:00
Daniel Agar 89e1f478ac PX4Accelerometer and PX4Gyroscope add vibration metrics and always publish status 2019-12-27 20:54:50 -05:00
Daniel Agar 176d7ef62d Jenkins PX4 ROS2 bridge don't specify python binary 2019-12-23 11:06:50 -05:00
Christian Clauss 6dc55f97d4 More fixes for Python 3 compatibility (#13008)
* More fixes for Python 3 compatibility

* Workaround if the six module is not pip installed

* Lose the semicolons
2019-12-19 02:05:55 -08:00
Timothy Scott 993fa5bd37 Refactored to work with new battery_status module 2019-12-05 16:38:04 +01:00
kamilritz b73c80428e ECL: Clean velPos logging, deprecate ekf2_innovations msg 2019-12-05 11:29:29 +01:00
Daniel Agar 709961ec8c
InvenSense ICM20602 and ICM20608-G: new standalone optimized drivers
- uses the FIFO and SPI DMA to transfer full raw data (8 kHz gyro, 4 kHz accel)
 - new sensor messages for better visibility
   - sensor_{accel, gyro}_fifo: full raw data for optional logging and analysis
   - sensor_{accel, gyro}_status: metadata, clipping, etc
 - currently not enabled by default
2019-12-03 23:21:32 -05:00
Daniel Agar 1a395fb6d9 ST ISM330DLC IMU driver 2019-12-03 16:16:49 -05:00
bresch 09c8c8f706 ekf: use PDOP instead of GDOP as TDOP (part of GDOP) is not given by the GNSS receiver 2019-11-27 10:33:27 +01:00
PX4 BuildBot 30fcb14156 Update submodule gencpp to latest Tue Nov 26 12:38:15 UTC 2019
- gencpp in PX4/Firmware (d5fb89ee02): 7e446a9976
    - gencpp current upstream: ff6c9f3e8e
    - Changes: 7e446a9976...ff6c9f3e8e

    ff6c9f3 2019-11-11 Jochen Sprickerhof - Two patches to make the generated headers reproducible (#42)
e12443e 2019-03-18 Dirk Thomas - 0.6.2
d227d17 2019-03-18 Dirk Thomas - update changelog
e233144 2019-03-15 Martin Pecka - Added plugins the ability to also generate free functions. (#40)
40559af 2019-03-04 Dirk Thomas - 0.6.1
96ec7f1 2019-03-04 Dirk Thomas - update changelog
2019-11-26 09:02:39 -05:00
PX4 BuildBot df0e4bfc62 Update submodule genmsg to latest Tue Nov 26 12:38:20 UTC 2019
- genmsg in PX4/Firmware (4f4e9c36fe3d0ecf547d50de9ca6b274e0f7ab65): 5736b1f7ad
    - genmsg current upstream: 1ad8e136cd
    - Changes: 5736b1f7ad...1ad8e136cd

    1ad8e13 2019-08-13 Dirk Thomas - Python 3 compatibility (#86)
ae81617 2019-08-12 AlexV - Rosimport improvements (#83)
f9dad2f 2019-03-04 Dirk Thomas - 0.5.12
0b2c12a 2019-03-04 Dirk Thomas - update changelog
2019-11-26 08:48:18 -05:00
TSC21 c9aab6319f microRTPS: update headers licenses 2019-11-26 09:01:52 +01:00
TSC21 54cd8f1856 microRTPS_client.cpp.em: fix double conversions 2019-11-26 09:01:52 +01:00
bresch 12177cb33b commander: add pre-flight check and parameter for magnetic field strength 2019-11-25 21:15:55 +01:00
TSC21 4c5e5acefe micro-CDR: bump submodule version and update CMake and src code 2019-11-24 19:36:00 -05:00
TSC21 d80da97ef5 micrortps_client: more cleanup 2019-11-24 21:39:01 +00:00
TSC21 ec0803815e microRTPS_client: use updated uORB API; improve usage 2019-11-24 21:39:01 +00:00
TSC21 16f53ec18d msg: add a deprecated uORB msgs list to CMake 2019-11-22 15:00:53 +01:00
Silvan Fuhrer ebdc29bc5f Airspeed Selector: enable airspeed_validated in control modules (#12887)
* FW attitude controller, FW position controller and VTOL attitude controller subscribe to airspeed_validated topic
* add possibility to switch off the airspeed valid checks
* remove airspeed valid checks from commander
* clean up of VTOL transition logic
* Airspeed Selector: remove dynamic allocation of airspeed validators (depending on number of connected sensors) but do it statically for the maximum number allowed. Check for number of connected sensors not only during start up, but always when vehicle is disarmed.
* Airspeed Selector: change work queue from lp to att_pos_ctrl as this module is safety-critical
* add airspeed selector to px4_fmu-v2 defaults
2019-11-21 14:14:25 -05:00
TSC21 16f663ad52 microRTPS bridge: fix UART baudrate set 2019-11-20 11:38:34 +00:00
Daniel Agar a2bd65460d commander: add vehicle-status nav_state change timestamp 2019-11-19 10:24:52 -05:00
JaeyoungLim 6bd4273b9c mavlink: handle cellular_status messages for logging 2019-11-13 09:19:02 -05:00
Peter van der Perk 991399f105 Added syncronization to t_send worker thread
Which avoids possible deadlocks
2019-11-08 18:58:38 +01:00
Beat Küng 6854b14dd6 esc_report: remove unused fields to reduce message size
esc_setpoint in UAVCAN was just wrong, this is what it really is:
uint7 power_rating_pct      # Instant demand factor in percent
(percent of maximum power); range 0% to 127%.
2019-11-07 10:40:03 +01:00
Beat Küng 0db0981b1b uavcan: remove actuator_direct (no publisher) 2019-11-07 10:40:03 +01:00
Peter van der Perk 08a27492b4 Introduced condition variable in ROS2 subscriber to solve 500ms latency spikes 2019-11-05 15:09:44 +00:00