- every incremental rebuild extended ${config_romfs_files_list}, the
chached variable was never reset
- cmake -E copy_directory did not remove deleted files
remaining issue: removing a file from the ROMFS & px4_add_romfs_files()
does not trigger the px_romfs_pruner.py COMMANDs to be re-executed.
It scales the yawspeed setpoint arbitrarily by default with 0.5.
This makes no sense because when you give a setpoint of 1rad/s then
you expect the setpoint to get executed. If you want manual yawspeed
response to be less agressive on the stick use the scaling parameter
for the stick MPC_MAN_Y_MAX.
- use mixer for the simulation to the sitl mixer dir
- do not use virtual elevator in the mixer for the real vehicle
Signed-off-by: Roman <bapstroman@gmail.com>
- P and D gains are too high for a racer
- default I gain is too low (0.25 is still quite low)
- use the thrust curve param instead of TPA
- improve responsiveness in Manual & increase max tilt angle to 60 degrees
- enable one-shot
- enable high-rate logging profile
- disable RC filter
When SYS_USE_IO was disabled, px4io would not start and thus there was no
RC. SYS_USE_IO=0 is interesting on Quads to avoid the IO and reduce output
latency.
Tested on Pixhawk 1 and Pixhawk 4
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
* Lists ROMFS files explicity instead of using GLOB_RECURSE
Previously, when ROMFS files that were not airframes were touched, the ROMFS
would not be rebuilt. The ROMFS files are now specified explicityl in a
CMakeLists.txt file that is located in the root ROMFS directory.
Now when one of the ROMFS files is touched the whole ROMFS is rebuilt.
When new files are added to the ROMFS, they need to be explicity added to
the CMakeLists in the ROMFS root directory.
* ROMFS: adds individual CMakeLists files in each subdirectory
Also moves the temporary ROMFS build directory to ${PX4_BINARY_DIR}/ROMFS/genromfs
so that the cmake_install.cmake files and the CMakeFiles directories (generated whenever
are not add_subdirectory() is called) are not generated in the temporary ROMFS directory
from which the ROMFS binary is created.
* cmake ROMFS generate add px4_add_romfs_files function
* ROMFS CMakeLists: adds explanatory comment to px4_add_romfs_files function
* ROMFS CMakeLists: updates copyright headers
- need to make some flash space for fmuv2 to avoid user confusion about
why it wind estimator only runs on some platforms
Signed-off-by: Roman <bapstroman@gmail.com>
- increase the minimum pwm value for multirotor mode since we experienced
the rear motor stalling in certain situations when throttle was low
Signed-off-by: Roman <bapstroman@gmail.com>
Because the parameter does not make sense from a control theory
perspective. Either you have a gain with the unit 1/s or an inverse
gain or time constant with the unit s. But the time constant parameter
was neither bound to any exact unit nor did it apply instead of a gain.
Rather it adjusted multiple gains from rate and attitude control
according to an arbitrary scale. This can only by accident lead to
good tuning.
- this makes sure that all motors are idling in mc mode. having this too
low can lead to a motor stopping in flight which is critical for
attitude control
- experienced loss of attitude control in RTL during descent prior to this
change
Signed-off-by: Roman <bapstroman@gmail.com>
- move to ModuleBase
- strip down to PWM 8 and 16 modes only
- remove all dead code
- implement missing pwm ioctls (current value, rates, etc)
- default rate 50Hz -> 400Hz
- simulated tailsitter needs a virtual elevator since we cannot simulate
elevons yet (liftDrag plugin does not model longitudinal moment Cm)
Signed-off-by: Roman <bapstroman@gmail.com>
The geometry was previously quad_deadcat in which front motors are closer to CG and thus more loaded in hover.
quad_wide is the same geometry as quad_deadcat except the CG is centered so all motors are loaded equally.
Flight logs on IRIS with deadcat mixer showed that
- all motors are equally loaded during hover (actuator_outputs 0 to 3 have similar values)
- a negative pitch offset is building up soon after takeoff (visible in actuator_controls)
- SYS_FMU_TASK is now enabled for PX4FMU_V4 PX4FMU_V4PRO PX4FMU_V5, but
it's only set on autoconf
- v5 companion is now TELEM2 (same as all other boards)
Adding a seperate cmake config to support RTPS messaging on AeroFC. This will
include compiling protocol_splitter and micrortps_client, and starting both
of them at boot time.
The config mode uses high rates for many streams, leading to high CPU usage
(9-10% for the mavlink sender). The normal mode contains almost the same
set of messages but at lower rates.
This reduces the CPU load on a Pixracer by 3-4%.
This commit is an attempt to fix a race condition happening on takeoff
between the land detector and the multicopter position controller.
Previously, an auto-takeoff leads to the following events:
1. A takeoff setpoint is given.
2. The thrust setpoint spikes because we don't enter smooth takeoff yet.
3. The land detector detects a takeoff because of the high thrust.
4. The position controller sees the landed state transition and
initiates the smooth takeoff. Thrust goes back down.
5. Depending on control gains the takeoff is successful or fails
if the smoothing takes too long which causes thrust to be too low, so
the land detector detects land again.
The two obvious problems with this are:
- The intermittent spike.
- The failed takeoff because of the smoothing leads to a delay..
With this change, the logic for a takeoff detection is moved from the
land detector to the position controller.
The events are now:
1. A takeoff setpoint is given.
2. The position controller detects the takeoff setpoint and initiates
the smooth takeoff.
3. As thrust ramps up, the land detector detects the take off.
In the same way, we now detect the intent to takeoff in manual,
altitude, control, position control in the position controller instead
of in the land detector.
* NuttX cmake
* px4_macros:Pass the stringified predicate as second arg to static assert
CC_ASSERT mapes to the c++ static_assert or provides the same
funtionality for c via the other macros. The c++ static assert
takes 2 argumants the prdicate and a message. This fixes the
lacking second argument.
* Updated nuttx and apps submodule to upstream nuttx 7.21+==master
This is the latest uptake of upstream nuttx and apps.
* ROMFS generate with xxd instead of objcopy
* delete nuttx-patches
* NuttX update submodules to latest px4_nuttx-master
* fix nuttx apps and board dependency
* docker_run update to latest container 2017-08-29
* cmake ROMFS portable sed usage
* NuttX update submodules to latest px4_nuttx-master
This commit changes old trone driver into a generic
TeraRanger driver that supports both TeraRanger One
and TeraRanger Evo.
As a part of the change a new parameter was created
SENS_EN_TRANGER that allows to specify the following
modes of operation:
0 - sensors disabled
1 - autodetect sensors
2 - use TeraRanger One rangefinder
3 - use TeraRanger Evo rangefinder
Signed-off-by: Mateusz Sadowski <msadowski90@gmail.com>