Subscription::update() already copies data into the destination buffer,
making the subsequent copy() call redundant. This eliminates an
unnecessary memcpy every cycle on the 400 Hz rate control loop.
Note that internally higher update rates are likely also not useful but this needs to be carefully checked with the interface. It seems like the ADSB driver keeps track of what to publish when which is not a scalable/well-testable solution.
- Use %*s in state_listing() to skip filepath that was parsed but never used
- Remove unused opendir()/closedir() in log_entry_from_id()
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
- Size LogEntry.filepath to PX4_MAX_FILEPATH instead of hardcoded 60 bytes
- Add width specifier to sscanf calls to prevent buffer overflow
- Move platform defines from .cpp to .h for reuse
- Add static_assert to enforce scanf width < buffer size at compile time
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
The mavlink_tests module was deleted in 1009268d311 but several
references were left behind, breaking builds on all targets.
Removed:
- CMakeLists.txt: add_subdirectory(mavlink_tests)
- mavlink_ftp.cpp: #include of deleted mavlink_ftp_test.h
- mavlink_ftp.h: MavlinkFtpTest forward decl and friend class
- posix-configs/SITL/init/test/test_mavlink: dead init script
- sitl_tests.cmake: sitl-mavlink CTest target
- install-voxl.sh: px4-mavlink_tests symlink
Ref: https://github.com/PX4/PX4-Autopilot/issues/26738
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Reject Zenoh payloads that exceed the expected uORB topic size plus
CDR header (4 bytes), or that are too small to contain a valid CDR
header. This prevents a stack overflow from crafted network input
where z_bytes_len(payload) controls a VLA allocation.
Fixes GHSA-69g4-hcqf-j45p
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Use logical OR (||) instead of AND (&&) in _workWrite() and _workBurst()
session validation, matching the correct logic already used in _workRead()
and _workTerminate(). The AND operator allowed operations to proceed with
an invalid session ID as long as a valid file descriptor existed.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Remove the old MAVLINK_FTP_UNIT_TEST infrastructure that has been dead
code for years (not enabled in any board config). This includes:
- src/modules/mavlink/mavlink_tests/ directory (test suite, CMakeLists)
- All #ifdef MAVLINK_FTP_UNIT_TEST blocks in mavlink_ftp.cpp
- set_unittest_worker() callback mechanism in mavlink_ftp.h
- Conditional uAvionix include in mavlink_bridge_header.h
The test suite will be ported to GTest as a follow-up.
Ref: https://github.com/PX4/PX4-Autopilot/issues/26738
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Add bounds checking in the CAN frame assembly loop to prevent a buffer
overflow when copying payloads into the Tattu12SBatteryMessage struct.
A crafted CAN frame with a corrupt payload_size could write past the
48-byte struct boundary. Also guard against payload_size of 0 which
would cause an unsigned integer underflow on the size_t subtraction.
Fixes GHSA-wxwm-xmx9-hr32
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Variable-length known packet types (CRSF_PACKET_TYPE_ELRS_STATUS,
CRSF_PACKET_TYPE_LINK_STATISTICS_TX, CRSF_PACKET_TYPE_MSP_WRITE)
bypassed the bounds check that exists for unknown packets. A crafted
packet with a large size field could overflow the 64-byte process_buffer
during QueueBuffer_PeekBuffer() in the CRC state.
Apply the same CRSF_MAX_PACKET_LEN bounds check to variable-length
known packets that already exists for unknown packets.
Fixes GHSA-mqgj-hh4g-fg5p
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Reject replies with length >= sizeof(BSTPacket) to prevent OOB read
in CRC calculation. Clamp dev_name_len to buffer size to prevent OOB
write during null termination.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
* docs(ekf2): clarify EKF2_HGT_REF param description
To me it was not obvious that with EKF2_GPS_CTRL=0 this altitude
initialisation based on GPS again does not apply.
* docs(ekf2): separate paragraph