Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Spacecraft Modules Stack (DISCOWER#10)
* failsafe framework: inform about failsafe action * Additions to the Serial UART API (PX4#22953) - Added an empty constructor, setPort, and validatePort functions for Serial API - Changed GPS to not allocate Serial object dynamically - Moved access check on serial port name into the Serial API - Improved the Qurt platform validatePort Serial function to implement a more rigorous check. Added safety check to the setPort Serial function to make sure it isn't called after the port has been already opened. * Qurt termios decoy (PX4#22954) * Added decoy termios support to Qurt so that ghst parser in RC library can be used. No termios is actually needed but has to be there for the parser to work * gps: fix Septentrino serial read (PX4#22936) For Septententrino we seem to sometimes fill the buffer pretty full. If we ask for too much, readAtLeast will fail completely and make the GPS discovery logic fall over. Therefore, let's not ask for too much and just read what we can given the available buffer. Signed-off-by: Julian Oes <[email protected]> * drivers: barometer: ms5837 fix compilation error Fixes MS5837.cpp:343:29: error: 'T' was not declared in this scope by using last temperature instead * drivers: tap_esc: fix Werror=maybe-uninitialized compilation * examples: matlab_csv_serial: fix compilation Update uORB definition and sprintf float formatting * systemcmds: microbench: %s doesn't except nullptr use "null" instead * systemcmds: reflect: write return needs to be used for werror checks * drivers: transponder: don't free pre-allocated memory * drivers: uavcan: fix werror uninitialized error * drivers: vector: Fix PX4 SITL x86 compilation * drivers: bmi088_i2c: Enforce I2C driver can only be used when SPI version isn't selected Solves multiple references compilation errors * drivers: cyphal: Fix ARM/x86 printf werror portability error * v6x-rt: Split ITCM static and auto-generated functions * kconfig: Add dependencies * modules: zenoh: remove broken serial config and update topics * cmake: all allyes target for better CI coverage Currently only v6x-rt and SITL are supported But targets with label allyes will try to enable all kconfig symbols * Port CRSF RC driver to new Serial UART API (PX4#22917) * Added implementations of Rx Tx swap and single wire for new UART API needed by CRSF driver * Added inverted mode to Serial interface API * boards: new hkust nxt-fc board support (PX4#22961) * logger: make logging of rtl_status not optional Signed-off-by: Silvan Fuhrer <[email protected]> * logger: reduce interval of rtl_status logging Signed-off-by: Silvan Fuhrer <[email protected]> * px4io: remove special handling for HITL In HITL the actuators should not be mapped and they are in lockdown. We should not reconfigure disarmed, min, max PWM values without updating the actual output values because the IO will consider the last outputs before the FMU was rebooted with the configuration of the new boot. This can result in spinning motors when switching to SIH. * px4iofirmware: refactor to only have one PWM output code path This removes the duplication with unexpected differences and allows to consistently handle the output instead of overriding the output for some specific cases which leads to unexpected corner cases. E.g. disabled outputs suddenly outputing PWM in lockdown. * px4iofirmware: simplify lockdown logic * px4iofirmware: reuse existing disarmed logic for lockdown and `should_always_enable_pwm` The existing disarmed logic already handles disabled outputs it makes sense to reuse it and not have lockdown handled differently resulting in unexpeced corner cases. * Build new IO firmware binaries * battery: weigh voltage based estimate more when it's low This is a minimal change to make it harder to crash a vehicle with an empty battery if the capacity was set wrong. The disadvantage is that the state of charge estimate will fluctuate more under load. We need better documentation and improvements to the estimation. * boards/modalai/voxl2: added device specifier to gps start line * Jenkinsfile - dual-deploy uorb graph and failsafe to vitepress (PX4#22943) * px4io: Fix dependency problem caused by PX4#22957 * Serial: removed the validateBaudrate function from nuttx and posix platforms and just send out a warning it baudrate is non-standard (PX4#22969) - Fix some Qurt platform build issues uncovered when changing the posix version of SerialImpl * gz-bridge: use correct prev_timestamp for dt calc - with the addition of the navsat plugin in PR#22638, the callback would reassign the previous timestamp used in the calculations of the angular_velocity causing derivative type noise in the groundtruth measurements * Memsic MMC5983MA magnetometer driver * msg: update VehicleCommand.msg MAV_CMD_DO_REPOSITION comment Added missing MAV_CMD_DO_REPOSITION parameters, from MAVlink Docs. * ekf2: use global definition of quaternion error * ekf2: improve tilt leveling speed Starting with no yaw uncertainty makes the tilt more observable when using fake position fusion during the quasi-stationary alignment phase. * ekf2: integrate mag heading into mag 3D * ekf2: limit mag heading fusion to prevent heading overconfidence * ekf2: do not continuously use mag decl fusion when GNSS fusion is active This prevents over-constraining the heading from mag fusion. An incorrect mag yaw rotation can be absorbed as a declination error. * ekf2: remove option to continuously fuse mag declination Declination fusion is only used when not observable (no global aiding). * ekf2: update change indicator * Navigator: remove unused method Signed-off-by: Silvan Fuhrer <[email protected]> * FeasibilityChecks: only require both or neither TO/LND when landed Signed-off-by: Silvan Fuhrer <[email protected]> * Mission params: update description of MIS_TKO_LAND_REQ Signed-off-by: Silvan Fuhrer <[email protected]> * drivers: rc_input only publish if more than 0 rc channels filled (fixes GHST auto scan) * px4_fmu-v6x:Add Holybro Pixhawk Jetson Baseboard ver 0x100 * Send mavlink manual control buttons field in manual control input topic (PX4#22988) Pass along button states from manual control mavlink message in new buttons field in manual control input topic * Vuepress removal /changes for vitepress (PX4#22972) * Vuepress removal /changes for vitepress * generate_msg_docs.py - README is index in vitepress * Update NuttX * Move Voxl from microdds client to uxrce dds client * Enabled voxl2-slpi dsp_sbus driver in build * drivers: broadcom AFBR fix close to ground false readings * mission_base: fix to set the end of mission item always, if the mission can't be properly loaded or started * FW position control: catapult/hand-launch: do not cut throttle if not landed Signed-off-by: Silvan Fuhrer <[email protected]> * FW position control: catapult/hand-launch: enable without launch detection Signed-off-by: Silvan Fuhrer <[email protected]> * TECS: check if integrator update is finit prior applying Signed-off-by: Silvan Fuhrer <[email protected]> * MissionBase: hasMissionLandStart should only return true if mission is valid Signed-off-by: Silvan Fuhrer <[email protected]> * RT: only chose mission RTL if mission is valid Signed-off-by: Silvan Fuhrer <[email protected]> * remove PGA460 from COMMON_DISTANCE_SENSOR * remove LIS2MDL from COMMON_MAGNETOMETER * boards: ARK Pi6X Initial Commit * airframes: Droneblocks DEXI 5 * delete SYS_MC_EST_GROUP - introduce per module parameters (EKF2_EN, LPE_EN, ATT_EN) - add basic checks to prevent EKF2 + LPE running simultaneously * Added high rate esc_status logging to the high rate logging category along with actuator_outputs_debug. Both of these really help diagnosing odd flight behavior / crashes on VOXL2. Also changed the logger start commands in the VOXL2 standard and HITL startup scripts. * lib/rc/dsm: update proto init to have reset incorporated as well (PX4#22995) * update voxl2-slpi spektrum_rc driver * Voxl new board specific module (voxl_save_cal_params) to save calibration parameters (PX4#22993) * Added Voxl board specific module to save calibration parameters in QGC format * Document vehicle attitude message * Add python script to translate C param to new yaml file * order yaml fileds * ekf2: migrate param to yaml * logger: add timesync_status to default logged topics Signed-off-by: Beniamino Pozzan <[email protected]> * Update CMakeLists.txt - included lawn world Added lawn world to make process to allow gz sim building like "make px4_sitl gz_r1_rover_lawn" * Updated GZ submodule to the latest hash (d754381) * remove clip_limit contraint on INT16_MAX * Fix up notes boxes for docs (PX4#22999) * Fix up notes boxes for docs * Update markdownout.py * Update markdownout.py * Update markdownout.py * ekf2: set horizon using specific parameter Some sensors can have their delay included in the timestamp. In this case, the buffer cannot be sized using the _DELAY parameter. * Voxl ESC driver update (PX4#23022) * Made Serial API open the UART in NON BLOCKING mode * Updated voxl_esc driver to latest from ModalAI fork * Ported voxl_esc driver over to new Serial UART API * Removed voxl_esc serial abstraction since new Serial API is already a serial abstraction * ekf2: move yaw_estimator and derivation to dedicated folder * drivers/optical_flow/paw3902: fix RegisterRead udelay * drivers/optical_flow/paa3905: fix RegisterRead udelay * fw offboard control mode: altitude control enabled (PX4#23041) * adsb: warnings fixes & remove UTM_GLOBAL_POSITION (PX4#21663) - warn about full traffic conflict buffer at 1/60hz. - add conflict expiry for buffer. - use only events for buffer full warning. mavlink_log_critical no longer needed. - use icao address for conflict warnings id, stop using uas_id. UTM_GLOBAL_POSITION assumed deprecated. - stop spamming when buffer is full - fix warning wording if buffer is full. - remove UTM_GLOBAL_POSITION Fixes failing unit test: * [adsbTest] Reduce conflict timestamps - not enough time has passed in ci - failed ci output - (passes locally with make tests TESTFILTER=AdsbConflict) - Timestamp: 6000000000 - Time now: 457720038 - Time since timestamp: 0 - Old Conflict warning expired: 0 - -------------------- - adsb_conflict._traffic_state 0 - ../../src/lib/adsb/AdsbConflictTest.cpp:244: Failure - Value of: adsb_conflict._traffic_state == TRAFFIC_STATE::REMIND_CONFLICT - Actual: false - Expected: true * bmp388: check bus return code after register read Check I2C/SPI bus transfer function return code after register read operation. Signed-off-by: Tero Salminen <[email protected]> * feat: adding thruster effectiveness * feat: updates to module yaml and naming of classes * feat: added actator type and updated thruster effectiveness * feat: update cmake lists for added modules * fix: compiling with thrusters inside * feat: added spacecraft effectiveness - to be validated * baro comp: set hpf optional * feat: fixed allocator bug - need to remove prints * CMakeLists: install_python_requirements allow --break-system-packages * fix: control allocator running with thrusters! * rft: removed prints and non-required messages * feat: renamed MC_ and mc_ to SC_ and sc_, added gains on airframe for tuning * feat: adding attitude rate ctl * PM Selector Auterion: remove INA226_SHUNT value reset (skynode only) * autopilot_tester: use normal VTOL mission for airspeed blockage test Signed-off-by: Silvan Fuhrer <[email protected]> * autopilot_tester: reduce mission distance for wind world Signed-off-by: Silvan Fuhrer <[email protected]> * autopilot_tester: for mission end timeout check take speed factor into account And increase the (simulation time) timeouts. Signed-off-by: Silvan Fuhrer <[email protected]> * fix: actuator testing and att control. Att control needs further work * chunk: fixes towards full pipeline * feat: functionThrusters in mixer module * ekf2_params: reduce "short" description * imu consistency: don't scale param threshold * simulation/gz_bridge: eliminate implicit float conversion * VSCode: add EditorConfig extension to recommended and devcontainer.json * fix to orientation offsets for scaled yaw, removed unused param Signed-off-by: dirksavage88 <[email protected]> * Shift vertical orientation above scaling yaw operation, cp angle sign change Signed-off-by: dirksavage88 <[email protected]> * drivers/magnetometer: new ST IIS2MDC Magnetometer driver * commander: set correct health component when reporting errors * commander: fix check for availability of high latency link Signed-off-by: RomanBapst <[email protected]> * high_latency_stream: fixed bug where fields were not updating - topic update was checked twice in the same loop and thus the second time the topic would never indicate to have updated Co-authored-by: RomanBapst <[email protected]> * mavlink: fix handling of transmission enable/disable Co-authored-by: RomanBapst <[email protected]> * commander: improve handling high latency link lost/regain * mavlink: use high_latency_data_link_lost as backup to normal data_link * mavlink: don't send events over Iridium * mavlink: don't send command ACK for internal commands over Iridium * iridiumsbd: update logic for detecting if the modem is not responsive * mavlink: use high_latency_data_link_lost as backup to normal data_link * telemetry: enable iridium * high_latency_stream: heading taken from vehicle_attitude topic * commander: fixed format * mavlink: added back gimbal v1 protocol command * high_latency_stream: minor PR fix * telemetry: removed iridium driver * mavlink: fixed compilation error after var renaming * MC Auto: add fixed yaw mode * estimatorCheck: get param only if handle is valid * init: creating spacecraft position controller * add: params * px4_cli: Added px4_get_parameter_value function overload for float type * mavlink: Added parsing of CLI option to configure HL frequency * mavlink: Added MAV_{i}_HL_FREQ parameter * boards: removed CONFIG_SYSTEMCMDS_REFLECT from Sky-Drones AIRLink board support * FW Position Controller: fix Altitude mode without valid z reference (e.g. no GPS) Signed-off-by: Silvan Fuhrer <[email protected]> * fix: major changes to position control for compatibility with spacecraft * fix: nan on setpoints for att control * imxrt: flexpwm remove 1:1 mapping requirement * feat: cleaning position controller * fix: updated empty trajectories * doc: small changes to att control - will move to different branch * fix: several fixes on attitude controller cleaning * LogMessage.msg - expand out descriptive string (PX4#23054) * commander: Use PX4_STACK_ADJUSTED to increase stack for 64-bit targets Signed-off-by: Jukka Laitinen <[email protected]> * ekf2: Only reset to GNSS heading if necessary When North-East (e.g.: GNSS pos/vel) aiding is active, the heading estimate is constrained and consistent with the vel/pos aiding. Reset to GNSS heading should only occur if no N-E aiding is active or if the filter is not yes aligned. Otherwise, just wait for the consistency check to pass again (will pass at some point if the heading uncertainty of the filter is getting too high). * libevents: update submodule And remove obsolete libevents_definitions.h * feat: updates to attidude control * ekf2: GPS yaw only invalidate yaw_align if stopping due to fusion failure * boards: update ark_pi6x EKF delays * boards: add iis2mdc mag to ark pi6x * gps: add ZED-F9P-15B * boards: ark rtk gps safety led open drain * gps: split enum after rebase Signed-off-by: Julian Oes <[email protected]> * drivers/ins/vectornav: add missing sensor_gps velocity magnitude * NuttX with imxrt_sd-preflight backport * px4_fmu-v6xrt:Support_MMCSD_MULTIBLOCK with preflight * fix: remove FW_ARSP_MODE * fix: doubled topcis * add: manual subscription * add: debug attitude setpoint in dds, more updates on control stack * sensors/vehicle_angular_velocity: silence gyro selection fallback warning (PX4_WARN -> PX4_DEBUG) - this warning was to catch any potential errors in sensor selection relative to what's actually available, we don't need to complain about initial selection before the EKF selector is available * sd_bench: Add U option for forcing byte aligned Co-authored-by: David Sidrane <[email protected]> * ekf2: move EV files to aid_sources/external_vision * ekf2: move auxvel file to aid_sources/auxvel * ekf2: move drag_fusion file to aid_sources/drag * ekf2: move GNSS files to aid_sources/gnss * ekf2: move optical flow files to aid_sources/optical_flow * ekf2: move gravity fusion file to aid_sources/gravity * ekf2: move baro height file to aid_sources/barometer * ekf2: move sideslip fusion file to aid_sources/sideslip * ekf2: move airspeed fusion file to aid_sources/airspeed * ekf2: move range finder files to aid_sources/range_finder * ekf2: move output predictor to output_predictor/ * ekf2: move mag fusion to aid_sources/magnetometer * ekf2: move aux global position fusion to aid_sources/aux_global_position * ekf2: move bias estimators to bias_estimtor/ * ekf2: move fake_height, fake_pos, zero_innovation_heading to aid_sources/ * ekf2: move terrain estimator and derivation to terrain_estimator/ * ekf2: move IMU down sampler to imu_down_sampler/ * ekf2: move baro dynamic pressure compensation to aid_sources/barometer * ekf2: delete unused Ekf::resetImuBias() * ekf2: move Ekf::resetQuatStateYaw() to yaw_fusion.cpp * ekf2: move gyro/accel/wind covariance reset helpers to covariance.cpp * ekf2: ekf_helper.cpp remove duplicate method comments (comment on declaration only, not definition) * drivers: adis16507 reschedule reset after failed self test * fix mavlink: cmd_logging_{start,stop}_acknowledgement flags were not reset Regression from PX4#23043 Also avoids a race condition by making sure the command ack is handled before sending out the mavlink message (in case an external component reacts immediately to the mavlink message). * fix: aiming for static position and attitude keeping * fix: attitude setpoint updates only when needed * dbg: behavior seems consistent, need to ensure it works on position mode * feat: position control needs to be tested - arming pos ctl not working * Tools: skip submodule check in CLion Same as what's required for VSCode. Signed-off-by: Julian Oes <[email protected]> * feat: adding parameters to replicate hardware pwm for spacecrafts * fix: added fixes for vision/mocap data. * Update submodule * rft: removing undesireable prints * mavlink_ftp: handle relative paths correctly by ensuring there's a '/' in between when concatenating the path with _root_dir. * mavlink_ftp: ensure there's enough space for the 2. path in _workRename Prevents accessing invalid memory when reading ptr + oldpath_sz + 1 and oldpath_sz fills out the whole or N-1 bytes of the payload. * mavlink_ftp: do not store reply on kErrNoSessionsAvailable This would interfere with an existing ongoing session * TECS: allow for fast descend up to maximum airspeed. Use pitch control loop to control max airspeed while giving minimal throttle. * TECS: increase airspeed control limit for fast descend * TECS: enable specific energy weights to have a value up to 2 * TECS:use tas_setpoint instead of measured tas for specific kinetic energy calculation * gps: Change the IF statement to a SWITCH statement * quadchute: fixed sign for handling altitude resets Signed-off-by: RomanBapst <[email protected]> * boards: ark septentrio gps add iis2mdc * increased uxrce-dds stack size to prevent overflow * gps: add note to param This notes the reference yaw angle for the Septentrio Mosaic-H. It's unfortunately a bit tricky in that Unicore has the main antenna in front by default while Septentrio decided to put the aux antenna in front. Signed-off-by: Julian Oes <[email protected]> * fmu-v6xrt: Enable debug features for more verbose hardfault output * fmu-v6xrt: Add I2C driver launcher * feat: updating thruster plugin on gazebo-classic sitl * fix: format checks * fix: disabled unit tests for spacecraft - they need to be designed * add: empy, might fix fails * fix: reverting changes to workflow * feat: updating Gazebo Classic submodule commit * fix: submodules * fix: commits from submodules * Add manual force control for spacecraft Use setpoints in manual mode for now Add scaling parameters F * fix: fixed styles and configuration files for spacecrafts based on feedback * fix: init.d cmakelists * fix: removed MyMessage, replaced with MavlinkLog * feat: 6dof spacecraft updates * feat: updated thrust of DART spacecraft * feat: added frictionless world * fix: compilation issues with fmuv6x * fix: thruster output range to match hardware * fix: failsafe on invalid posctl now is stabilized mode * dbg: position control * fix: ensuring manual is separate from acro * dbg: rate control + qgc consistency * fix: scaling of simulated output for thrusters * feat: set proper naming and frames for QGC * fix: fix PID of rate control, needs cleanup * fix: added rates publisher and fixed logic for stabilized mode * doc: updated comments * feat: updates to SITL and to controllers * fix: tuned rate ctl * fix: add att tuned gain * fix: position control * rft: clean prints --------- Signed-off-by: Julian Oes <[email protected]> Signed-off-by: Silvan Fuhrer <[email protected]> Signed-off-by: Beniamino Pozzan <[email protected]> Signed-off-by: Tero Salminen <[email protected]> Signed-off-by: dirksavage88 <[email protected]> Signed-off-by: RomanBapst <[email protected]> Signed-off-by: Jukka Laitinen <[email protected]> Co-authored-by: Matthias Grob <[email protected]> Co-authored-by: Eric Katzfey <[email protected]> Co-authored-by: Julian Oes <[email protected]> Co-authored-by: Peter van der Perk <[email protected]> Co-authored-by: Peize-Liu <[email protected]> Co-authored-by: Silvan Fuhrer <[email protected]> Co-authored-by: Hamish Willee <[email protected]> Co-authored-by: henrykotze <[email protected]> Co-authored-by: Jacob Dahl <[email protected]> Co-authored-by: Noe S. Sanchez <[email protected]> Co-authored-by: bresch <[email protected]> Co-authored-by: Alex Klimaj <[email protected]> Co-authored-by: David Sidrane <[email protected]> Co-authored-by: Eric Katzfey <[email protected]> Co-authored-by: Konrad <[email protected]> Co-authored-by: Jacob Dahl <[email protected]> Co-authored-by: Daniel Agar <[email protected]> Co-authored-by: JaeyoungLim <[email protected]> Co-authored-by: Kalyan Sriram <[email protected]> Co-authored-by: Beniamino Pozzan <[email protected]> Co-authored-by: Sergei Grichine <[email protected]> Co-authored-by: Juyong Shin <[email protected]> Co-authored-by: asimopunov <[email protected]> Co-authored-by: Tero Salminen <[email protected]> Co-authored-by: fury1895 <[email protected]> Co-authored-by: Thomas Frans <[email protected]> Co-authored-by: dirksavage88 <[email protected]> Co-authored-by: Beat Küng <[email protected]> Co-authored-by: Igor Mišić <[email protected]> Co-authored-by: RomanBapst <[email protected]> Co-authored-by: oravla5 <[email protected]> Co-authored-by: murata,katsutoshi <[email protected]> Co-authored-by: Jukka Laitinen <[email protected]> Co-authored-by: Benjamin Philipp Ketterer <[email protected]>
- Loading branch information