Commit Graph

26875 Commits

Author SHA1 Message Date
PerFrivik 1e7ce32480 Differential Rover: Added logging and dds topics 2023-12-21 16:27:53 +01:00
PerFrivik 3df71d1837 Differential Rover: Differential drive module & library 2023-12-21 16:27:53 +01:00
Peter van der Perk 19d1941758 px4_fmuv6xrt: Switch to icm42686p on SPI1
icm42588p driver don't use a icm42688p when icm42686p is requested
2023-12-21 10:11:20 -05:00
bresch c1b139dea1 atune: reset param on start
This prevents a race condition where autotune cannot start because the param was already set to 1
2023-12-21 13:52:47 +01:00
MaEtUgR 74549e29a5 [AUTO COMMIT] update change indication 2023-12-21 11:42:08 +01:00
Matthias Grob bcb2b1ad40 matrix: fix slice to slice assignment to do deep copy
To fix usage of a.xy() = b.xy() which should copy
the first two elements over into a and not act on a copy of a.
2023-12-21 11:42:08 +01:00
Silvan Fuhrer 2afbd09c63 Commander: AirspeedCheck: increase timeout threshold to 2s
1s gives some false positives at boot up, as the airspeed selector only
starts publishing 2s after its startup.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
Silvan Fuhrer 9d00a3ae4d AirspeedSelector: remove option to disable airspeed sensor through ASPD_PRIMARY
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
Silvan Fuhrer 29807a5e50 Replace CBRK_AIRSPD_CHK with SYS_HAS_NUM_ASPD
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
Silvan Fuhrer 9e0c8fd75e FW controllers: change param FW_ARSP_MODE to FW_USE_AIRSPD
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
Silvan Fuhrer 1f2a0bc657 Commander: remove check for FW_ARSP_MODE for airspeed missing reporting
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
Silvan Fuhrer 5211c358aa FW Position Controller: change airspeed setpoint init
-remove dedicated vtol transition airspeed init logic
-init airspeed setpoint on first usage of tecs
-init to max of current airspeed and min airspeed

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
Silvan Fuhrer 27957e1f2f FW Position Controller: set airspeed_valid flag to false if incoming data is not finite
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
Silvan Fuhrer 123c06f2e6 NPFG: specify in comments that airspeed reference is for true airspeed
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
Silvan Fuhrer 589f0f1fc7 FW Position Controller: rename _airspeed to _airspeed_eas
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-21 11:34:28 +01:00
bresch b8c81f6281 gps_blending: fallback to secondary if primary has no fix 2023-12-20 16:35:30 -05:00
bresch 094048ed04 gps_blending: fix selection rapid switching
Once a timeout of the primary instance is detected, a fallback is only
allowed until the primary receiver is regained.
2023-12-20 16:35:30 -05:00
bresch 36eb319834 ekf2-yaw_est: split imu and velocity updates 2023-12-18 18:11:20 +01:00
bresch bba30663cc update change indicator
Caused by the GNSS checks being performed at the delayed-time horizon
2023-12-18 18:11:20 +01:00
bresch a653073d4f ekf2: perform GNSS checks at delayed-time horizon
- never fuse a measurement that is not passing the checks
- cleanup and simplify GNSS vel/pos control logic
2023-12-18 18:11:20 +01:00
Frederik Markus 65e53286b6
Standalone px4 stable (#22467)
simulation gazebo: move the gazebo models to submodule, allow for operation with external gazebo instance, independent of startup order. Allows drag an drop of models from gazebo fuel.

* rolled back updates

Signed-off-by: frederik <frederik@auterion.com>

* fixing empy

Signed-off-by: frederik <frederik@auterion.com>

* Update GZBridge.cpp to lower drop position 

Dropping from 1m leads to movement in the rc_cessna. Dropping from 0.5m leads to no movement.

* Update STANDALONE env variable.

* Update STANDALONE env_variable on GZBridge

* Update src/modules/simulation/gz_bridge/GZBridge.cpp

Co-authored-by: Daniel Agar <daniel@agar.ca>

* test removal of x500

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* removed all models and reworked logic

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* remove model path in set_sdf_filename

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* filter resource path for world sdf

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* updated structure to keep old make px4_sitl

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* remove gz tools

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* import gz as submodule and reverse rc simulator logic

Signed-off-by: frederik <frederik.anilmarkus@gmail.com>

* [gz-sim]: source GZ_SIM_RESOURCE_PATH only if PX4 starts gz server

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>

* Typo fix

---------

Signed-off-by: frederik <frederik@auterion.com>
Signed-off-by: frederik <frederik.anilmarkus@gmail.com>
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
Co-authored-by: Daniel Agar <daniel@agar.ca>
Co-authored-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
2023-12-18 09:43:20 +01:00
Matthias Grob 6ffc5a9eae
events: pass relative paths plus base path to source parser script (#22551)
* events: pass relative paths plus base path to source parser script

to work around maximum Makefile command lenght limits.

* events: correct cmake comment typo

Co-authored-by: Beat Küng <beat-kueng@gmx.net>

---------

Co-authored-by: Beat Küng <beat-kueng@gmx.net>
2023-12-18 09:33:53 +01:00
Silvan Fuhrer f38fe24a98 FW Position Control: fix setting of _control_mode_current to AUTO in VTOL landing
The _control_mode_current wasn't updated otherwise, and only done so by luck
because we already set the current type to SETPOINT_TYPE_POSITION.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-16 16:37:51 -05:00
Daniel Agar 4b25fad862 lib/timesync: relax warnings
- double required max consecutive counts
 - don't continuously complain about round trip time (RTT) unless
   there's been at least one acceptable round trip (latency < 100 ms)
2023-12-16 16:36:36 -05:00
Daniel Agar dba2d76321
systemcmds/i2c_launcher: fix USER_I2C_LAUNCHER kconfig warning 2023-12-16 16:28:11 -05:00
Silvan Fuhrer 8be22f6c75 FW Position Controller: add missing @decimal 1 for FW_LND_THRTC_SC
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-16 09:45:18 +01:00
oystub 24cee81279 gps_blending: output valid time_utc_usec
Before this fix, the time_utc_usec output from blending was always 0.
This means that you wouldn't get a valid vehicle_gps_position/time_utc_usec

With this commit, UTC timestamps are blended according to weights for
all GPSes with a nonzero UTC timestamp value.

It would be possible to simply use the first valid UTC timestamp instead
of blending, but since the system timestamps are blended, it seems
suitable to blend UTC timestamps as well.
2023-12-13 11:14:00 -05:00
Niklas Hauser c769fc7785 SF1xx: optionally disable sensor in forward flight 2023-12-13 09:02:26 +01:00
marcojob cf62dad28d
sensors/VehicleAngularVelocity: fix force SensorSelectionUpdate
- This fixes the force call on SensorSelectionUpdate
 - In contrary to the rest of the codebase, this method also takes a timestamp: When you call SensorSelectionUpdate(true), time_now_us is actually set to 1 and force stays false, as this is the default value for in the method.
2023-12-12 20:56:59 -05:00
Kjersti Brynestad 91e3ec5884 mavlink: Handle NAMED_VALUE_INT 2023-12-12 20:50:46 -05:00
GuillaumeLaine 942b6700a1 dds_topics: export estimator_status_flags 2023-12-12 14:43:07 -05:00
Silvan Fuhrer 91ab09ebd5 TECS: in _calcPitchControlOutput guard against invalid airspeed inputs
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-12 15:16:38 +01:00
Silvan Fuhrer 9db86f7f0a TECS: fix airspeed filter init in airspeed-less mode
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-12 15:16:38 +01:00
Silvan Fuhrer 60e2c6a5cb TECS: improve initialization
-remove external init, and instead always (but only) init when dt is too large
-init the controller params correctly

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-12 15:16:38 +01:00
Silvan Fuhrer 1f5fc3e849 TECS: init control params to reasonable values
The control params (eg min/max pitch) are used before they are
correctly set by TECS::update(). While this is an issue we should fix,
it also doesn't hurt to set them to more reasobale values (eg 30° limit).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-12 15:16:38 +01:00
Silvan Fuhrer 7926107328 TECS: make sure to constrain pitch to current min/max pitch
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-12 15:16:38 +01:00
Silvan Fuhrer cc743048ba TECS: set _ratio_underspeed to 0 if airspeed disabled
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-12 15:16:38 +01:00
Matthias Grob ece60b6165 msp_osd: reuse existing mode name conversion
This saves a bit of flash, keeps the mode names up to date and
works like expected.
2023-12-11 17:29:45 +01:00
Silvan Fuhrer 8aab3e8013
Navigator: same logic for VTOL_TAKEOFF as for TAKEOFF (#22518)
Set the setpoint type to POSITION if already in air, not to TAKEOFF.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-11 14:18:22 +01:00
Matthias Grob ebae9ae3d7 FlightTaskManualAccelerationSlow: MC_ prefix for parameter names
As discussed in the maintainer call we should adhere to the
parameter naming scheme that makes it clear what vehicle type the
configuration is good for.
2023-12-08 21:17:59 +01:00
Matthias Grob d03030e881 mavlink_receiver: ifdef guard for velocity limits
Since this message is defined in development.xml and
not yet common.xml and some targets use
common.xml and the builds then failed.
2023-12-08 21:17:59 +01:00
Matthias Grob ca6db94e39 Velocity limit: remove duplicate message and if(true) 2023-12-08 21:17:59 +01:00
Matthias Grob da24811ce1 SickAccelerationXY: fix comment typo brak{e}ing 2023-12-08 21:17:59 +01:00
Marcin 4cf43a68a3 FlightTask: add subscription to VELOCITY_LIMITS msg 2023-12-08 21:17:59 +01:00
Matthias Grob 54ce9813c8 FlightModeManager: Add task for position slow mode 2023-12-08 21:17:59 +01:00
Matthias Grob ef0926d64b Commander: add position slow mode 2023-12-08 21:17:59 +01:00
Matthias Grob dbbf585adb StickYaw: yaw rate limit interface 2023-12-08 21:17:59 +01:00
Matthias Grob 84220407ea FlightTaskManualAltitude: vertical velocity limit interface 2023-12-08 21:17:59 +01:00
Matthias Grob bb617f6c4d FlightTaskManualAcceleration: horizontal velocity limit interface 2023-12-08 21:17:59 +01:00
Matthias Grob 77c06a9f9e Sticks: Provide auxiliary analog values from manual_control_setpoint 2023-12-08 21:17:59 +01:00
Matthias Grob df41bc3d26 StickAccelerationXY: make sure speeds below 1m/s are exactly reached
by only applying the sqrt linear drag when brakeing.
It was originally not done this way to avoid discontinuities and
the exact speed bewlo 1m/s didn't matter. With the position slow mode
the exact slow speeds now matter. And the discontinuities are avoided by
reusing the brake boost filter.
2023-12-08 21:17:59 +01:00
Daniel Agar f703f07399
drivers/distance_sensor: update kconfig common sensors
- mappydot is EOL
 - LL40LS_PWM is a fairly special case that's not common
2023-12-08 13:32:23 -05:00
Matthias Grob e35380d6ae mixer_module_tests: cover `output_limit_calc_single()` 2023-12-07 21:35:55 -05:00
Matthias Grob 0a78690356 mixer_module: correct output_limit_calc_single calculation 2023-12-07 21:35:55 -05:00
PX4 BuildBot fb3123e33b Update world_magnetic_model to latest Thu Dec 7 11:14:08 UTC 2023 2023-12-07 21:34:18 -05:00
PX4 BuildBot db1bb94ea4 Update submodule mavlink to latest Thu Dec 7 12:39:06 UTC 2023
- mavlink in PX4/Firmware (67cf6bd264055a5d13d5521c6c43bd5b42f374ca): 6cf005e996
    - mavlink current upstream: 5f85bd7d7d
    - Changes: 6cf005e996...5f85bd7d7d

    5f85bd7d 2023-12-07 Hamish Willee - MAV_CMD_DO_SET_HOME - add home position roll/pitch (#1849)
55ba3887 2023-12-06 Hamish Willee - Fixed deprecation typo for MAV_CMD_SET_MESSAGE_INTERVAL (#2060)
2023-12-07 17:56:13 -05:00
PX4 BuildBot 3d1ce20c12 boards: update all NuttX defconfigs 2023-12-07 17:55:38 -05:00
Silvan Fuhrer c61ac784b6 FW attitude controller: remove deprecated ecl_controller
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-07 17:21:09 +01:00
Silvan Fuhrer b1317daa9c wheel controller remove from ecl
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-07 17:21:09 +01:00
Silvan Fuhrer 00f5bba5e0 FW att controller: wheel controller: separate from ecl_controller
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-07 17:21:09 +01:00
Silvan Fuhrer 448292c980 FW att controller: yaw controller: separate from ecl_controller
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-07 17:21:09 +01:00
Silvan Fuhrer d4206195c6 FW att controller: pitch controller: separate from ecl_controller
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-07 17:21:09 +01:00
Silvan Fuhrer 7e467f7121 FW att controller: roll controller: seperate from ecl_controller
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-07 17:21:09 +01:00
Silvan Fuhrer 48782723ab FW att controller: ecl_controller: move setter/getter implementation to header
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-07 17:21:09 +01:00
Matthias Grob 14c4257a59 ActuatorEffectivenessRotors: Use modern parameter interface for rotor count
This lead to a compiler warning with arm-none-eabi-gcc 12+
about the variable count potentially being a dangling pointer.
2023-12-05 12:06:56 -05:00
bresch 5ca22df55c ekf2-pos bias estimator: use enum 2023-12-05 11:22:59 -05:00
bresch a3515a2474 ekf2: scope HeightSensor enum 2023-12-05 11:22:59 -05:00
bresch 6bd1145006 ekf2: scope RngCtrl enum 2023-12-05 11:22:59 -05:00
bresch 1df52df27d ekf2: scope GnssCtrl enum 2023-12-05 11:22:59 -05:00
bresch 97423136d1 ekf2-AGP: scope control enum 2023-12-05 11:22:59 -05:00
Beat Küng c5101c70b3 uorb: enure message definitions don't exceed buffer lengths & increase test buffer
There were already checks at runtime, but this ensures the format is not
too long at built-time.
2023-12-05 10:42:23 +01:00
Konrad df46ad7774 Dcm2: Use std::sin with overloaded types 2023-12-05 10:42:23 +01:00
Konrad d1b8a2e8d5 fxedwingPositionControl: Add slew rate at the end for all mode instead inside each 2023-12-05 10:42:23 +01:00
Konrad 1d07697a9e NPFG: Add fallback for corner cases 2023-12-05 10:42:23 +01:00
Matthias Grob 1c25d65a1e Add missing newline at the end of files 2023-12-01 13:11:00 -05:00
Matthias Grob 4c0b6dbe86 Remove trailing whitespaces and trailing duplicate newlines 2023-12-01 13:11:00 -05:00
Matthias Grob d8d2213cab mavlink streams: add SYSTEM_TIME to onboard low bandwidth
It's required with 2Hz by some MAVLink enabled payloads.
2023-12-01 11:02:37 -05:00
Matthias Grob 9184a8f4ef mavlink streams: add CAMERA_IMAGE_CAPTURED to onboard low bandwidth 2023-12-01 11:02:37 -05:00
Matthias Grob 3ceb932b7c mavlink streams: increase RC_CHANNELS rate for onboard low bandwidth
There are MAVLink enabled gimbals that directly consume RC channel data.
The gimbal controls stutter with this profile when the rate is too low.
2023-12-01 11:02:37 -05:00
Matthias Grob 938be68c69 mavlink streams: add gimbal orientation feedback to normal stream
It only publishes when the information is available on uORB
and is useful for the groundstation to show the gimbal's status.
2023-12-01 11:02:37 -05:00
Silvan Fuhrer b0df7c7ccb RTL/Land: set gimbal to neutral to reduce change of damage
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-01 13:19:09 +01:00
Silvan Fuhrer 789b3880cf Mission: set gimbal to neutral on inactivation
It is generally preferred to have the camera pointing forward on pause,
e.g. to use the camera for Navigation.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-01 13:19:09 +01:00
Silvan Fuhrer 0d8ba587ca Mission: set gimbal to neutral before landing item
To reduce risk of damage during landing.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-01 13:19:09 +01:00
Silvan Fuhrer 178ea132b6 Navigator: add set_gimbal_neutral() functionality
To point the gimbal forward eg during landing to reduce chance of damage.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-01 13:19:09 +01:00
bresch fe7988672f ekf2: auxiliary position fusion
Co-authored-by: Daniel Agar <daniel@agar.ca>
2023-12-01 11:50:22 +01:00
Matthias Grob 8bb20db7da GotoControl: Save flash 2023-11-30 17:16:02 +01:00
Matthias Grob 7b4712cb29 sensor_simulator: initialize VelocitySmoothing with desired limits 2023-11-30 17:16:02 +01:00
Matthias Grob d014d76ca7 HeadingSmoothing: set correct maximum heading
The velocity smoothing library constrains the maximum vellocity.
I set the default constraint to 0 to find these exact issues.
The heading smoothing did not initialize the maximum velocity
which in this use case is the maximum heading.
So heading was always constrained to 0 -> north until this change.
2023-11-30 17:16:02 +01:00
Matthias Grob 5a2efc1cb2 GotoControl: remove dependency on PositionControl
It was there only to have the empty trajectory setpoint defined.
I rather redefine it for the single use.
2023-11-30 17:16:02 +01:00
Matthias Grob c853acc2ff GotoControl: also provide maximum velocity to position smoother 2023-11-30 17:16:02 +01:00
Matthias Grob d1e8bdbd16 GotoControl: rename yaw rate acceleration parameter
such that not only one letter differs to MPC_YAWRAUTO_MAX
2023-11-30 17:16:02 +01:00
Matthias Grob dc7f9165d1 logged_topics: fix goto_setpoint name 2023-11-30 17:16:02 +01:00
Matthias Grob 3de6fee07f GotoControl: make interface over uORB 2023-11-30 17:16:02 +01:00
Matthias Grob 96a81c22e3 GotoControl: simplify configuration wrapping 2023-11-30 17:16:02 +01:00
Matthias Grob 439d6c61e0 Revise GotoControl 2023-11-30 17:16:02 +01:00
Matthias Grob 14b8afe972 PositionSmoothingTest: remove duplicate vector comparison 2023-11-30 17:16:02 +01:00
Matthias Grob 591845bb41 HeadingSmoothing: rename, simplify, add cpp 2023-11-30 17:16:02 +01:00
Matthias Grob be05b3e8d7 helper_functions: include defines for M_PI_PRECISE
The defintion of the custom symbol M_PI_PRECISE
was not included in one of the only places it's used.
Looks like a mistake that happened in
34c852255e
possibly because a lot of things are included
almost everywhere and if the include order
ligns up there are no compile errors.
2023-11-30 17:16:02 +01:00
Matthias Grob efb325d25d motion_planning: remove deprecated separate test
It's functionality probably broke already in
befbb6b106c4c04933222ecb205f001fd77fa85f
and the tests are now covered by
VelocitySmoothingTest.cpp
2023-11-30 17:16:02 +01:00
Matthias Grob 53076b9863 PositionSmoothing: guard division by zero
Note that the unit test also passes without
thechange. But the VelocitySmoothing's
local_time would get NAN. This would leads to
wrong trajectory calculations.
2023-11-30 17:16:02 +01:00
Matthias Grob 11cca72ef1 VelocitySmoothing: fix division by zero cases
Problem: Zero maximum jerk and/or zero
direction would lead to divisions by zero in
various cases depending on the exact configuration and code path.

Solution: There was already one check for the
direction being zero in one path and I
summarized to check in both
updateDurations...() functions the product
of direction * max_jerk to not be zero
because that's exactly the value calculations
devide by.
2023-11-30 17:16:02 +01:00
Matthias Grob 6f295d91d1 Revert "motion_planning: sanitize inputs to position and velocity smoothing libs"
This reverts commit 2951c846ee07e52c2e3d97ea4629185016f3a011.
2023-11-30 17:16:02 +01:00
Thomas Stastny 4b920a6628 GotoControl: add go-to control interface to mc position controller
goto control class handles smoothing of goto setpoints, outputs trajectory setpoint for mc pos control
some minor encapsulation done in mc pos control for readability
new param MPC_YAWAAUTO_MAX limiting heading accelerations in heading smoother
2023-11-30 17:16:02 +01:00
Thomas Stastny e47aba8bc9 msg: add go-to setpoint interface 2023-11-30 17:16:02 +01:00
Thomas Stastny 72a811a4b3 motion_planning: add heading smoother lib
wraps the velocity smoother, but is intended for generating smooth heading trajectories
handles angle wrap
2023-11-30 17:16:02 +01:00
Thomas Stastny 80dd7e4806 motion_planning: sanitize inputs to position and velocity smoothing libs 2023-11-30 17:16:02 +01:00
Jukka Laitinen 9d465615d1 src/drivers/sw_crypto: Fix buffer lengths for xchacha20 crypto
The size input argument for monocypher crypto_xchacha20_ctr should be the
plaintext message length.

The promise of the interface is, that the call to encrypt_data updates the
ciphertext message length after the call succeeds.

The crypto should check that the output buffer length (cipher length) is
large enough to contain the encrypted data.

Fix these issues; these have gone unnoticed for a long time since the interface
has been only used by logger, and passing the same size for both in and out.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2023-11-29 20:56:00 -05:00
PX4 BuildBot c2345ac5b3 Update world_magnetic_model to latest Wed Nov 29 11:14:09 UTC 2023 2023-11-29 20:55:05 -05:00
PX4 BuildBot 33a3e568bb boards: update all NuttX defconfigs 2023-11-29 20:54:34 -05:00
Jacob Dahl e627fe01dc UXRCE_DDS_SYNCC default 0 2023-11-29 20:53:01 -05:00
Konrad 42ce9eb692 mavlink_mission: Send MISSION_CURRENT periodically even when no mission is loaded. 2023-11-29 11:10:40 -05:00
Konrad 36f0c0f0bf mavlink-mission: Add support for opaque ids and replace update counter with it 2023-11-29 11:10:40 -05:00
Konrad 120e7fea8b mavlink: update submodule including opaque ID 2023-11-29 11:10:40 -05:00
Frederik Markus f00d97d974
removal of PX4_GZ_MODEL env variable and fix of ground glitching (#22400)
Removal of PX4_GZ_MODEL env variable and fix of ground glitching

Signed-off-by: frederik <frederik@auterion.com>
Co-authored-by: frederik <frederik@auterion.com>
Co-authored-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
2023-11-29 09:08:04 +00:00
alexklimaj 59abab8379 sensors: add parameter to silence imu clipping 2023-11-28 11:57:14 -05:00
Daniel Agar a9213e3862
Update world_magnetic_model to latest Tue Nov 28 11:14:14 UTC 2023
Co-authored-by: PX4 BuildBot <bot@px4.io>
2023-11-28 11:04:02 -05:00
PerFrivik befbc19a4a Roboclaw: Updated parameter prefix for roboclaw output module 2023-11-28 16:30:17 +01:00
PerFrivik c84185af96 Roboclaw: Fixed issue where parameters had different prefixes 2023-11-28 16:30:17 +01:00
PerFrivik 9ce090f2da Roboclaw: Fix CI pr issue 2023-11-28 16:30:17 +01:00
PerFrivik 7c45093908 Roboclaw: Updated yaml file to support Roboclaw Driver in QGC 2023-11-28 16:30:17 +01:00
PerFrivik de9074558b Roboclaw: Updated Airframe and fixed left and right mapping error 2023-11-28 16:30:17 +01:00
PerFrivik 09d30568ab Roboclaw: Consistent Left & Right naming convertion with Differential Drive class 2023-11-28 16:30:17 +01:00
Matthias Grob f53edfa440 Roboclaw: major cleanup 2023-11-28 16:30:17 +01:00
Matthias Grob c27181a154 Rename RoboClaw -> Roboclaw
The manufacturer uses both naming schemes, RoboClaw more than Roboclaw
but it's always one word and hence I think it's more consistent to name
it the latter.
2023-11-28 16:30:17 +01:00
Matthias Grob 87683aa790 Roboclaw: move parameters to module.yaml 2023-11-28 16:30:17 +01:00
Matthias Grob 8f4ce28e84 RoboClaw: declutter, make it compile again 2023-11-28 16:30:17 +01:00
Matthias Grob 5b4031356e RoboClaw: fix style 2023-11-28 16:30:17 +01:00
Per Frivik 9409646a89 Update RoverPositionControl.cpp 2023-11-28 16:30:17 +01:00
PerFrivik a40120c332 Roboclaw: Integrated OutputModuleInterface including a large code refactor 2023-11-28 16:30:17 +01:00
PerFrivik 86e5561a64 Roboclaw: Fixed issue when power cylcing the roboclaw where the driver would not connect 2023-11-28 16:30:17 +01:00
PerFrivik 524fa73ad3 Roboclaw: rough refactor, removed repetitive code, simplified and clarified logic and error handeling 2023-11-28 16:30:17 +01:00
PerFrivik dde7bbb4f6 Roboclaw: Initial cleanup, next commit will be refactor removing the duplicated write and read functions 2023-11-28 16:30:17 +01:00
PerFrivik fe4d319ba9 Roboclaw: Replaced setDutyCycle with setMotorSpeed to allow for encoder data to get through (added support for encoders) 2023-11-28 16:30:17 +01:00
PerFrivik c7e780cb6d Roboclaw: Working temporary version that drives around 2023-11-28 16:30:17 +01:00
PerFrivik 184993daa3 Roboclaw: Added DutyCycle command in Roboclaw destructor to turn off motors 2023-11-28 16:30:17 +01:00
Matthias Grob a857df88e4 Driving possible 2023-11-28 16:30:17 +01:00
PerFrivik ab486de430 Roboclaw: Temporary fix, enabling driver to run 2023-11-28 16:30:17 +01:00
PerFrivik 549c6b565c ported roboclaw driver from older commits into newest develop branch 2023-11-28 16:30:17 +01:00
Konrad 8a68a66203 figureEight: Rename relative position variable 2023-11-28 10:06:01 +01:00
Konrad 1e06ed2ed5 figureEight: Rework initialization 2023-11-28 10:06:01 +01:00
Konrad a73409c015 FigureEight: Refactor initialization 2023-11-28 10:06:01 +01:00
Beniamino Pozzan 2363c03bfe [uxrce_dds_client] wait for Timesync to converge
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
2023-11-27 21:10:26 -05:00
Beniamino Pozzan f01400de81 [uxrce_dds_client] Fix debug string format - use PRId64 and llabs
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
2023-11-27 21:10:26 -05:00
Daniel Agar 5af6cf1889
Update submodule GPS Drivers to latest Tue Nov 28 00:39:22 UTC 2023
- GPS Drivers in PX4/Firmware (5ef3ae3f1ec5aecea5842306a63aec054eb599a9): 6e452c2c5b
    - GPS Drivers current upstream: 63990d218e
    - Changes: 6e452c2c5b...63990d218e

    63990d2 2023-11-22 Daniel Agar - nmea fix astyle whitespace

Co-authored-by: PX4 BuildBot <bot@px4.io>
2023-11-27 21:05:23 -05:00
PX4 BuildBot dfbd5c88b1 Update submodule mavlink to latest Tue Nov 28 00:39:31 UTC 2023
- mavlink in PX4/Firmware (b8870adb3e2002ee16ebf63bd23342a055ab8628): 70181c42fc
    - mavlink current upstream: 02f1575d73
    - Changes: 70181c42fc...02f1575d73

    02f1575d 2023-11-24 Hamish Willee - MAV_CMD_CONDITION_YAW - shortest direction v2 (#2058)
bc0d8611 2023-11-22 Roman Bapst - moved MAV_CMD_EXTERNAL_POSITION_ESTIMATE from ardupilotmega to common (#2057)
b85e0016 2023-11-22 Hamish Willee - development - delete MAV_CMD_SET_FENCE_BREACH_ACTION (#2053)
2023-11-27 20:40:31 -05:00
Silvan Fuhrer 2734c44533 FlightTaskAuto: set state to None if prev and current sp are equal
Otherwise if is set to Offtrack, which in turn leads to weird behavior.
E.g. when triggering Land while flying fast forward, the vehcile doesn't
descned to the land point it keeps getting a velocity setpoint from the
smoother that pushes it away from the land point.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-11-27 18:01:47 +01:00
Konrad 6a34b63b60 mission_base: perform mission_check_valid if mission, geofence ot homeposition have changed 2023-11-24 08:11:41 +01:00
Konrad 5e1f0b73ce HomePosition: Add an instance counter 2023-11-24 08:11:41 +01:00
Konrad 3ac7ed6afa mission_base: Do not reset mission on invalid mission upload 2023-11-24 08:11:41 +01:00
Konrad a92e7a8796 missionResult: remove unnecessary constants and rename instance_count to mission_update_counter 2023-11-24 08:11:41 +01:00