- allow effectiveness matrix to select control allocator method
(desaturation algorithm)
- add actuator_servos publication
- add support for multiple matrices (for vtol)
- add updateSetpoint callback method to actuator effectiveness to allow it
to manipulate the actuator setpoint after allocation
- handle motor stopping & reversal
- add control surfaces & tilt servos
- handle standard vtol + tiltrotor
- rename MC rotors params & class to be more generically usable
- fixes and enables ActuatorEffectivenessRotorsTest
This fixes a case where the px4 startup is not stopped when the
px4 process is killled using -SIGKILL against the px4 deamon.
In that case, the currently executing command/client is killed
and properly shutting down with result -1, however, the next command
is started anyway.
This means that the next time we try to run the simulation we get a
"PX4 daemon already running for instance 0" error and PX4 doesn't start
properly.
By adding exit on error, we properly exit in the case where the startup
script gets stopped/killed.
- cmake NuttX build wrapper compile in place instead of copying source tree to build directory
- slightly faster skipping necessary copying (depending on system)
- allows debugging in place
- easier to work directly in NuttX following official documentation
- simplifies overall build which should make it easier to resolve any remaining NuttX dependency issues in the build system
- the downside is switching back and forth between different builds always require rebuilding NuttX, but I think this is worth the improved developer experience
- also no longer builds px4io and bootloader in every single build, for most users these rarely change and we're wasting a lot of build time
Remove params from airframe configs that are just set again
to the param default value or to the value that is
specified in the mc_default, fw_default or vtol_default.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- no longer start sercon or mavlink usb by default
- on USB connection (VBUS) monitor serial USB at low rate and start Mavlink if there's a HEARTBEAT or nshterm on 3 consecutive carriage returns
- the mavlink USB instance is automatically stopped and serdis executed if USB is disconnected
- skipping Mavlink USB (and sercon) saves a considerable amount of memory on older boards
Using mixers on the IO side had a remote benefit of being able to
override all control surfaces with a radio remote on a fixed wing.
This ended up not being used that much and since the original design
10 years ago (2011) we have been able to convince ourselves that the
overall system stability is at a level where this marginal benefit,
which is not present on multicopters, is not worth the hazzle.
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
Co-authored-by: Daniel Agar <daniel@agar.ca>
based on our experience with VTOL it makes sense to change the yaw mode default. You always want your VTOL to yaw in transition direction before starting the transition.
- include icm20948 on most boards by default
- create more test variants for default boards near flash limit (cuav_nora_test, cuav_x7pro_test, holybro_durandal-v1_test)
I don't think we should be broadcasting by default as we haven't done
that in the past. This suddenly spams the network with a lot of
messages, and leads to confusing situations in offices where there are
multiple PX4 SITL and QGC intances are open.
PX4 uses banks of 8 outputs as a logical structure. Boards that have
more outputs than 8 get multiple instances. This is an arbitrary choice
that helps with overall structure and enables the mixing of different
device classes (like FMU, IO or UAVCAN).
These changes remove the two code paths to updates (forceupdate and update) and try to reboot and bootload IO independent of its state, wether it is in bootloader mode already, safety switch is off or if it is in "nominal state" (running and safety on). This ensures that there are no conditions where user error or boot sequence can prevent a successful upgrade. The only state where an upgrade will not be done is if the system is fully armed.
Previously, we did not set a remote port which meant that the default
remote port 14550 was used. This meant that the mavlink instance
talking to the gimbal was interfering with the connection to the ground
station (on 14550).
This is a hack to make sure the messages from the gimbal arrive at other
links (e.g. the ground station). It means that the gimbal does not get
flooded with all other messages that would get forwarded but messages
from the gimbal will still make it through.
* Commit for the Integration of a position controller for the a Underwater vehicle.
This module is an extension of the uuv_att_control to control an Underwater vehicle to any position, given by the SET_POSITION_TARGET_LOCAL_NED which includes x y z yaw.
Since the position control is designed for a 6DOF Robot, the roll and pitch angle are controlled to be 0.
Additionally there is a stabilization control, which holds the robot at a defined depth, and not move in any direction.
In general the idea is to have this position module to control the position of the uuv. The position module reseives the desired position of the uuv and sends appropriate attitude setpoints to the uuv_attitude_control module.
Additionally the mixer file is adapted, to include the 6 different inputs(x y z roll pitch yaw).
* Commit for the Integration of a position controller for the a Underwater vehicle.
This module is an extension of the uuv_att_control to control an Underwater vehicle to any position, given by the SET_POSITION_TARGET_LOCAL_NED which includes x y z yaw.
Since the position control is designed for a 6DOF Robot, the roll and pitch angle are controlled to be 0.
Additionally there is a stabilization control, which holds the robot at a defined depth, and not move in any direction.
In general the idea is to have this position module to control the position of the uuv. The position module receives the desired position of the uuv and sends appropriate attitude setpoints to the uuv_attitude_control module.
Additionally the mixer file is adapted, to include the 6 different inputs(x y z roll pitch yaw).
Currently not solved/missing:
- Problem with gazebo model(propeller moving chaotically).
- Mixer correct gazebo vs real life (has to be tested in the future)
- correct integration in uuv.apps (when choose which module)
- very basic controller chosen (could be improved a lot in the future)
* Remove error caused by unused variables and a different build error
* added better description of the parameter. Additionally the group is changed.
* added better description of the parameter. Additionally the group is changed.
Fixed bug about parameter
* Added EOF to the files.
* Removed parameter for direct position control for safety reasons.
* small bugfix
This commit moves the steering output from yaw to the roll channel to better reflect the lateral control input / reaction mapping. It also removes old unused parameters and modernizes the mainloop to remove unnecessary polling.
This system command will display, set and save the network
settings.
netman show - Displays the current settings.
netman update - Will check for a net.cfg file on the SD card.
If present, it will update the paramaters,
delete the file, and reboot. Using the new settings.
netman save - Saves the current settings to net.cfg on the SD card.
This file shoulf be renamed to preserver it across
reboots or editited to chech networkin paramates.
File format is name<space>value:
echo DEVICE=eth0 > /fs/microsd/net.cfg
echo BOOTPROTO=fallback >> /fs/microsd/net.cfg
echo IPADDR=192.168.0.4 >> /fs/microsd/net.cfg
echo NETMASK=255.255.255.0 >>/fs/microsd/net.cfg
echo ROUTER=192.168.0.254 >>/fs/microsd/net.cfg
echo DNS=192.168.0.254 >>/fs/microsd/net.cfg
Valid values for `proto` are `dhcp`, `static`, `falback`
Both will try dhcp for CONFIG_NETINIT_FALLBACK times
and fall back to the static address.
NETMASK - is the network mask.
IPADDR - this nodes ip address for static or fall back.
ROUTER - The default route.
DNS - The address of the dns server.
- generate PWM_MAIN 1-14
- generate PWM_AUX 1-8
- generate PWM_EXTRA 1-8
- px4io and pwm_out directly read configuration parameters
- only available and active physical outputs are actually shown for configuration
- overall saves flash despite adding many new parameters
- 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>
- 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)
- 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>
- 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
* Add techpod SITL target
This adds a SITL target forthe techpod fixedwing model
* Update sitl_gazebo submoudle
This submodule update includes the techpod UAV model
- 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)
* Add jsbsim bridge to enable jsbsim for px4 SITL/HIL on jsbsim
This is a PX4 HIL/SITL integration into JSBSim. JSBSim is an open source flight dynamics model (http://jsbsim.sourceforge.net/)
Currently there are three models available which is the rascal, quadrotor_x, hexarotor_x integrated into the bridge.
The simulation can be run with the firmware with the following command for example
```
make px4_sitl jsbsim_rascal
```
The visualization is done flightgear and is done by the bridge sending UDP packets to flightgear. To disable the visualization `HEADLESS=1` when running the make command.
The simulation can be configured through the configuration files under the `config` directory through a xml file. Senor configurations, The xml file name should match the name of the model.
* Update Tools/sitl_run.sh
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
Nuttx now supports sh and source (.)
sh will open a new process for each invocation.
This means the child can not modify the parent
env. So we must use . to matain how nuttx worked.
Since rc.vehicle_setup is used in both we use
source and alis as we did with sh.
It loads the battery parameters but then overwrites them
with hardcoded values and it breaks the ModuleParams
parent/child hierarchy. Both is undesired.
* [WIP] i2c_spi_buses: add '-q' for quiet startup flag
And enable for optional board sensors.
* ROMFS: rc.sensors try starting all optional I2C sensors quietly
Co-authored-by: Daniel Agar <daniel@agar.ca>
- in practice this is mostly useful for identifying incorrect rotations
which we mostly have in 45 degree increments
- handling a vehicle on the ground can easily disturb one mag by more than 30 degrees, so this is often distracting noise
- the values of the parameters GND_MAX_ANG and GND_WHEEL_BASE are outdated. They belonged to another Rover setup.
- in the mixer file rover_diff_and_servo.main.mix the steering was controlled by roll, but in PX4 rover steering is controlled by yaw. And this was the reason why the attitude control did not work correctly
- the DF Robot GPX:Asurada rover has actual a steering angle of 60 degrees. And and wheel base of 0.17m. Parameter values in the airframe file are changed to this values
because we need to have SITL simulation as realistic as possible
compared to a real flight with default settings such that we
either fix the problems or adjust the defaults already in SITL testing.
- avoids the need for ekf2_timestamp publications by q and lpe
- adds logger to the lockstep cycle and makes it poll on ekf2_timestamps
or vehicle_attitude. This avoids dropped samples (required for replay).
- 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)
Before #14212 the velocity control gains used in the multicopter
position controller were defined as a scale between velocity error in
one axis (or it's integral and derivative respectively) and the unit
thrust vector. The problem with this is that the normalization of the
unit thrust vector changes per vehicle or even vehicle configuration
as 0 and 100% thrust get a different physical response. That's why
the gains are now defined as scale between velocity error
(integral/derivative) and the output acceleration in m/s².
- skip avionics rail voltage check when USB connected
- skip forced reboot on USB disconnect if circuit breaker set
- avionics voltage preflight check don't silently fail if system_power unavailble
- explicitly set supply check circuit breaker (CBRK_SUPPLY_CHK)
This adds a sitl target and aiframe configs for the r1_rover, which is a differential rover example for SITL rover. The model is based on the aion robotics r1 rover
Only have it higher for VTOL and fixed wing.
Multicopter position controlled flight is in our experience always <1g.
Acrobatic flying definitely exceeds the acceleration but if control
doesn't rely on the GPS velocity and position there shouldn't be any
problem.
-decrease L1 period for tighter mission tracking in fw mode
- increase backtransition duration, we can now do this is we have active
deceleration control
Signed-off-by: RomanBapst <bapstroman@gmail.com>
@fury1895 reported very valuable feedback from testing
the acceleration feed-forward on VTOL:
> MPC_JERK_MAX 4.5 (from 5 on it felt too aggressive)
> MPC_JERK_AUTO 4
> some hovering, some transitions, and a mission. Everything good.
> I'd say you feel the difference in position mode and you see it in
> Auto modes. Great improvement!
rc.io is called from 2 places in rc.interface:
- if [ $OUTPUT_MODE = io -o $OUTPUT_MODE = uavcan_esc ]:
- 'set OUTPUT_MODE io' is only set within USE_IO=yes, so removing
the check in rc.io has no effect.
- in case of UAVCAN, we also want the IO for RC, now covered in the next
case.
- Further down ('Start IO for RC input if needed.').
This is intended to start IO for RC only, when fmu is already started.
However the previous check '$USE_IO = yes' in rc.io prevented that.
In addition we don't start rc_input in case of $USE_IO = no.
Fixes no RC on Pixhawk 2 with SYS_USE_IO=0.