Commit Graph

41439 Commits

Author SHA1 Message Date
tanja 7097518373 px_uploader: Allow for multiple firmware files 2022-11-01 07:45:11 +01:00
benjinne c5c634be7f
lisXmdl: use I2CSPIDriverConfig (#20506)
- allows to configure the I2C address
- lis3mdl: add 2nd possible address to start
2022-11-01 07:42:27 +01:00
Matthias Grob afe1f82423 ver command: clarify PX4 version instead of FW version 2022-11-01 07:36:23 +01:00
JaeyoungLim a90857f651
FW separate reset integrals for messages (#20502)
This commit separates integral resets for attitude and rate control setpoints
2022-11-01 06:06:27 +01:00
Zachary Lowell 6d2dd798a0
Qurt drv_hrt Implementation (#20528) 2022-10-31 15:40:29 -07:00
Zachary Lowell 82f63475d7
Qurt work_queue Implementation (#20522) 2022-10-31 09:59:10 -07:00
Eric Katzfey 34c852255e
Changed M_PI to M_PI_F in the matrix library since M_PI is non-standard. (#20458)
* Changed M_PI to M_PI_F in the matrix library since M_PI is non-standard.

* Added a new M_PI_PRECISE constant definition to px4_platform_common/defines.h to be
used in places when M_PI is desired but shouldn't be used because it is not C standard.

* Added the px4_platform_common/defines.h include to the matrix library math.hpp header to pull
in some non-standard M_PI constants and updated the test files to use those constants.

* Fixed PI constants in matrix helper test to prevent test failure
2022-10-31 11:51:23 -04:00
Thomas Debrunner ba3f3935ab hardfault_log: Correctly annotate adddresses for the stack trace in the hardfault log. 2022-10-31 06:36:11 -04:00
JaeyoungLim 3f5d7f38cd
Handle waypoint altitude acceptance radius for boats (#20508)
This corrects the waypoint handling logic to include boat type vehicles
2022-10-31 09:13:13 +01:00
Julian Oes 21f49ff5be drivers: fix two includes for CLion
This fixes two errors where CLion complains:

error: 'size_t' does not name a type
2022-10-31 07:56:59 +01:00
PX4 BuildBot 80af8262b5 Update submodule mavlink to latest Sat Oct 29 12:39:05 UTC 2022
- mavlink in PX4/Firmware (f8b38591ac0bd31a87cb38ae4b2f7dd74400cda2): dda5a18ddb
    - mavlink current upstream: d012c7afd5
    - Changes: dda5a18ddb...d012c7afd5

    d012c7af 2022-10-27 Hamish Willee - update pymavlink to latest (#1906)
e1058881 2022-10-27 Hamish Willee - BATTERY_STATUS_V2 - update to 20221013 RFC version (#1846)
27007cc3 2022-10-25 Hamish Willee - fix typo MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST (#1904)
00007aca 2022-10-19 Hamish Willee - SET_DEFAULT_INTERVAL may be 0 (#1903)
af35d3a4 2022-10-09 Ashish Kurmi - ci: add minimum GitHub token permissions for workflow (#1898)
33dde554 2022-10-09 Siddharth Bharat Purohit - add vendor specs for cubepilot (#1901)
2022-10-29 10:56:25 -04:00
PX4 BuildBot a3caaa1372 Update submodule sitl_gazebo to latest Sat Oct 29 12:38:55 UTC 2022
- sitl_gazebo in PX4/Firmware (498937c56c): e804327595
    - sitl_gazebo current upstream: 56b5508b72
    - Changes: e804327595...56b5508b72

    56b5508 2022-10-13 junkdood - Update boat.sdf.jinja
2022-10-29 10:55:53 -04:00
Daniel Agar d4fb1b1f8b
Update submodule GPS drivers to latest Sat Oct 29 12:39:01 UTC 2022
- GPS drivers in PX4/Firmware (d67b19ac1d41b2dcfc61ed6d353ae513ac3f4a82): 1ff87868f6
    - GPS drivers current upstream: fa2177d690
    - Changes: 1ff87868f6...fa2177d690

    fa2177d 2022-10-10 Michael Schaeuble - Return from GPSDriverUBX::receive when ready, don't wait until no data is received

Co-authored-by: PX4 BuildBot <bot@px4.io>
2022-10-29 10:55:20 -04:00
Thomas Stastny 498937c56c fw rate control: initialize rate control resets to false in stabilized mode
before there was a corner case where if in an auto mode that sets a reset command on the attitude setpoint message (e.g. auto takeoff), if the mode was then switched stabilized, this reset bool would never be changed back to false and the integrators would reset every cycle
2022-10-28 09:26:51 +02:00
Zachary Lowell 824e02a8b6
Qurt tasks implementation (#20499) 2022-10-27 14:46:47 -07:00
Eric Katzfey fa74ee3d5b
perf: removed dprintf from perf library
* Removed dprintf from perf library since it is only ever used with fd=1 (STDOUT) so moved to PX4_INFO_RAW instead. This helps with some platforms (e.g. Qurt) which have some Posix support but not full Posix support.
2022-10-27 09:58:05 -04:00
Silvan Fuhrer 5edbc2f80a Navigator: remove update of reposition setpoint at Transition command
This was previously required to reset the flight speed after a VTOL transition,
but is now no longer required as the DO_CHANGE_SPEED commands are handles directly
in the controllers.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-27 11:04:22 +02:00
Silvan Fuhrer 473b471fb6 Navigator: add guards for using mission_item.loiter_radius only if finite and >FLT_EPS
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-27 10:28:05 +02:00
Silvan Fuhrer 605d4c47b9 Navigator: initialize _mission_item for all navigation modes in Navigator::Navigator()
This fixes the issue where the init happended in the initializer list, at which point
the params were not yet initialized and thus resulted in random values for the init
values of _mission_item.loiter_radius and .acceptance_radius.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-27 10:28:05 +02:00
afwilkin b834f2b5e3 README.md update for discord 2022-10-27 08:06:52 +02:00
Junwoo Hwang c2b2ae55d9 payload_deliverer: Refactor & Handle vehicle command conflicts
Refactor
- Require reboot for PD_GRIPPER_EN parameter change
- Define gripper ACTION_NONE for readability. This makes implicit assumption that -1 equals no-action commanded more explicit
- Tidy the scattered vcmd_ack struct handling cases into a single function
- Refactor to remove return in the middle of function: avoids future complications where a programmer may expect the logic at the end of the function to be executed, but isn't

Vehicle Command Handling
- Cancel the previous running vehicle command if we receive a different vehicle command
- Reject vehicle command if we get a same one that is getting executed
- Save the source system & component of currently running vehicle command
- Added note about new discovered edge case of having same entity sending different gripper commands consequently, where an unexpected ack result may be received
2022-10-27 07:51:17 +02:00
Junwoo Hwang 6529e39f8b payload_deliverer & gripper: Improve intermediate state & vcmd_ack
Gripper:
- Don't command gripper (via uORB `gripper` topic, which maps into an
actuator via Control Allocation) if we are already at the state we want
(e.g. Grabbed / Released) or in the intermediate state to the state we
want -> This prevents spamming on `gripper` topic

Payload Deliverer:
- Add read-once function for Gripper's released / grabbed state
- Send vehicle_command_ack for both release/grab actions.

TODO: target_system & target_component for the released/grabbed vcmd_ack
is incomplete, since we are not keeping track of the vehicle_command
that corresponds to this. This needs to be dealt with in the future, not
sure what the best solution it is for now.

Possible solutions:
- Queue-ing the vehicle command?
- Tying the gripper's action to specific vehicle command one-on-one, to make sure if we send multiple vehicle commands, we know
which command resulted in the action exactly?)

Only command Gripper grab when we are actually initializing gripper

- Previously, on every parameter update, gripper grab was being
commanded
- This commit narrows that scope to only when we are actually
initializing the gripper

Handle gripper de-initialization upon parameter change

- Also added some local state initialization code to init() function of
Gripper
- This will now make init / de-init more graceful & controlled compared
to before
2022-10-27 07:51:17 +02:00
Junwoo Hwang 36a3c716d6 Send IN_PROGRESS command ack when actuating gripper
- This hopefully then alerts the GCS that the command is getting
processed
- Referenced commander's `handle_command` function to implement this. As
it seems like GCS needs the acknowledgement of the command being
processed to execute such commands properly
- Also send FAILED command ack if we can't actuate the gripper

Fix wrong GRIPPER_ACTION conversion from floating point to int32_t

- Due to the MAVLink spec, we actually just convert enums into floating
point, so in PX4 we need to convert the float directly into integer as
well (although there can be precision issues on large numbers)
- This is a limitation in MAVLink spec, and should hopefully be
changed in MAVLink v2
2022-10-27 07:51:17 +02:00
Zachary Lowell eb16730400
Qurt IOCTL dependency addition (#20480) 2022-10-26 12:09:07 -07:00
Beat Küng 25fe13583e Jenskinsfile: use nuttx container as emscripten requires xz to be installed
Fixes the error:
Error: tar (child): xz: Cannot exec: No such file or directory
2022-10-26 14:54:48 -04:00
Zachary Lowell 740d2fccb1
qurt: update for functional logger 2022-10-25 21:07:15 -04:00
Zachary Lowell bcae7e550b
Qurt platform/common dependency fixes 2022-10-25 21:06:00 -04:00
Daniel Agar a242a0210e
Update world_magnetic_model to latest Mon 24 Oct 2022 09:29:11 PM EDT 2022-10-25 09:20:01 -04:00
Daniel Agar c32cf21b63 commander: estimator check shorten messages
- otherwise these are awkwardly split in mavlink
2022-10-25 08:02:47 +02:00
Daniel Agar a7b909234b commander: estimator nav test is not an arming check 2022-10-25 08:01:30 +02:00
Daniel Agar 6f861ba889 ekf2: pos/vel reset helpers pass new variance
- optical flow velocity reset use already computed _flow_vel_ne
2022-10-24 10:59:58 -04:00
thomas f9f466854b abort front transition in vtol module instead of in navigator/rtl.cpp 2022-10-24 13:55:41 +02:00
thomas 26c36a96f2 remove unnecessary check. correct int comparison. 2022-10-24 13:55:41 +02:00
thomas bf98503dec better return altitude initialisation 2022-10-24 13:55:41 +02:00
thomas f771c7ff63 back transition if RTL is called during front transition 2022-10-24 13:55:41 +02:00
Hamish Willee 96a305322a
params/uorb docs: rename mixer to control allocation (#20447) 2022-10-24 13:22:26 +02:00
Igor Mišić 1c5750b292 mavlink: add support for uAvionix transmitters 2022-10-24 11:56:17 +02:00
Igor Mišić c35ae7260b transponder/sagetech_mxs: move the ADS-B related parameters to the lib
ADS-B parameters can be reused for other ADS-B devices
2022-10-24 11:56:17 +02:00
Igor Mišić 4e6c094a54 mavlink/CMakeLists: add uAvionix dialect 2022-10-24 11:56:17 +02:00
Silvan Fuhrer 128e49358e Wind Estimator: remove filter reset due to beta fusion timeout
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-24 09:56:18 +02:00
Daniel Agar ed558e199f ekf2: remove realignYawGPS() (replaced with yaw estimator) 2022-10-21 09:01:30 -04:00
Silvan Fuhrer c267cf71c3 FW Position Control: fix entering of no-position-estimate failsafes
Affects the states AUTO_ALTITUDE and AUTO_CLIMBRATE. Those modes should only be entered
if armed (as they are pure failsafe modes). Also allow though to enter them even if
the position setpoint(s) are invalid, as they are not needed.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-21 09:51:38 +02:00
Silvan Fuhrer 67b2c835e0 FW Positon control: do not use position_setpoint.valid to validate current position_setpoint
Instead of checking the .valid flag of position_setpoint, check for ISFINITE() of lat, lon, alt
    when pulling the position_setpoint triplet. This fixes problems where the .valid flag didn't
    reflect the proper state of the setpoint (e.g. .valid was true, .lat though NAN)

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-21 09:51:38 +02:00
Silvan Fuhrer d8e483ae20 TECS: guard against NAN airspeed setpoints
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-21 09:51:38 +02:00
Eric Katzfey 4afd19f037 Moved the bad-function-cast compiler warning option out of the common flags and into
the nuttx and posix specific options files since this option cannot be used with
the qurt platform. There are header files in the hexagon sdk that fail this check.
2022-10-20 18:18:40 -04:00
bresch 96e7ea7a08 ekf2: remove old mag declination auto-code 2022-10-20 18:16:25 -04:00
bresch f0a0a3e545 ekf2_test: compare mag decl fusion sympy vs symforce 2022-10-20 18:16:25 -04:00
bresch 2f3ea88099 ekf2: migrate mag declination to SymForce 2022-10-20 18:16:25 -04:00
Beniamino Pozzan 7786437a19 Makefile: remove update_ros2_bridge make commands
as Tools/update_px4_ros2_bridge.sh as been deleted
update_ros2_bridge, update_px4_ros_com and update_px4_msgs
are no more needed

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
2022-10-20 17:43:16 -04:00
Daniel Agar 5030b21d2e ekf2: replace quatToInverseRotMat if only used once 2022-10-20 14:15:32 -04:00