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>
to get rid of derivative spikes when navigator is
continuously updating the yaw setpoint in the
triplet for a POI but is running at a lower rate.
The proper solution is to generate that yaw setpoint
with high rate in the flight task and have the triplet
just guid to the next waypoint at low rate.
Publishes periodically (max every 1 min) a warning if the current wind estimate
is above COM_WIND_WARN.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
to allow descending by stick for reliable land detection.
Issue:
Stick smoothing gets completely reset to state when not taken off
-> downwards velocity setpoint is gone when not taken off
-> in_descend flag of land detection is never true when not taken off
-> when landing but falling out of landing it landing detection fails
bafore taking off and landing again
Having a 2nd order low-pass filter in the derivative loop reduces
stability at low cutoff values as too much phase is lost through
the filter. Using a 1st order filter avoids this issue because its
maximum phase loss is 90 degrees instead of 180 degrees for a 2nd order
lpf.
This fixes the case where we sometimes switch to altitude control
instead of position control when RC is regained.
What happens is that we detect that the pilot wants to take over control
right when RC comes back. This means that we try to go in position
control in main_state_transition, however, we are already in position
control because we come back from the failsafe state. The result of
main_state_transition is then TRANSITION_NOT_CHANGED, and therefore we
"fall back" to altitude control even though being already in position
control would have been fine.
This fix checks the return result of main_state_transition correctly and
only reacts to TRANSITION_CHANGED and TRANSITION_DENIED but ignores
TRANSITION_NOT_CHANGED.
By default we would leave the LAND failsafe as soon as a link comes
back. With this change, we switch to the LAND failsafe like a proper
mode change, immediately disabling the failsafe as such.
This is as the same that is done for RTL in fact.
This is not optimal but a workaround for the problem where we switch out
of failsafe right on landing and then discover takeoff again and start
looping through it again and again without ever disarming.
I think it was not the best idea to use errno as a global variable to
keep track of the error code. I saw the errno change from where it was
set to where it was actually used, maybe because part of it is called in
the receive thread and part in the regular update/send() thread.
To be safe, I just created a class variable instead.
- initial frequency peak tracking SNR increased from 10->15 db
- after initial detection the threshold decreases to SNR 5db
- gyro_fft large method refactored into smaller pieces
- sensors/vehicle_angular_velocity: dynamic notch FFT make sample rate
check a percentage and relax lower bound safety threshold
- 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
SDLOG_ALGORITHM for selecting the crypto algorithm
SDLOG_KEY for selecting the key in keystore to use with the algorithm.
for symmetric algorithms which are currently supported, this is just a free
slot to be used, the key is generated at logging start
SDLOG_EXCH_KEY for selecting an RSA2048 key for encrypting the SDLOG_KEY
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This now only decrypts xchacha20 encrypted logs, where keys are
exchanged with rsa_oaep_sha256 and nonce appended to the end of the
key
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
- Generate a symmetric encryption key and a nonce value
- Use a public key in keystore to encrypt the symmteric key
- Write the encrypted key and the nonce value to disk into .ulgk, name matching with the encrypted log file
- use quick stream encryption to crypt the .ulg file contents
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Add common functions, implemented for nuttx, and link to architecture specific libraries
Make a separate library to wrap nuttx random number generator as "os_random".
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
By adding the sequence number we can avoid double triggering due to
command retransmissions. This is according to the mavlink spec for
MAV_CMD_IMAGE_START_CAPTURE.
VTOL planes are getting lift from the wing when flying in MC mode at
high speed. They (and some other drones) also get extra drag when
climbing and descending at high speed, corrupting the hover thrust
estimate.
To avoid this, two speed thresholds (vertical and horizontal) are defined
above which the sensitivity of the estimator is decreased by linearly
increasing the observation noise.
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>
Currently only for the Z axis. If the current downward velocity is more
than twice the maximum allowed value, the emergency braking mode is
activated. In this mode, a higher vertical acceleration and jerk is used
until the vehicle stops moving.
* fix disable airspeed check with negative ASPD_FS_INTEG
* improve logic when nav velocity data is not good
* simplify logic. Reset integrator state when the check is not run.
I usually called it using `source arch.sh`
but if it's executable it could also be called using `./arch.sh`
and that's also what's done for the ubuntu setup script.
This is to avoid potential race conditions during startup.
All startup code runs sequentially atm, so this is just for robustness
for later (e.g. concurrent pwm_out and dshot start).
This allows modules to do a first-come-first-serve pin/timer reservation
on bootup.
E.g. camera trigger reserves any of the pins, and then PWM/DShot output
will just use the rest of the available pins.
EKF2 has a grace period of 10 seconds after boot where it doesn't need
to warn the user while the sensors (especially GNSS) are still
converging.
A connection to a GCS shouldn't skip this grace period but
an arming request should.
- This driver is highly specific to this model of Tattu battery and cannot work with other models without code changes.
- The driver simply reads CAN frames using the NuttX CAN character device interface and converts the data into the proper format as specified in the Tattu datasheet
Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
The clock is simply not accurate enough to do that.
Plus the measuring overhead is much higher than the executed instruction.
Remaining issue: memory transfers (due to volatile) add non-negligible
overhead and distort the result. Could be solved by using inline assembly.
This is needed in case the bootloader configured the MPU, which could interfere with the app as the bootloader memory map / configuration is different.
When the last WorkItem is deleted, it is removed from a work queue and the
queue is being stopped. But, the queue itself might get deleted in the middle,
in a higher priority thread than where the WorkItem deletion was performed from
If the WorkQueue::Detach accesses the member variables after this, there is memory
corruption
This happens in particular when launching i2c or spi devices in
I2CSPIDriverBase::module_start:
- The "initializer" is deleted when the instance is not found and the iterator
while loop continues.
- The workqueue is deleted in the middle of "initializer" deletion when the
WorkQueueRunner returns.
This prevents deletion of the WorkQueue before the Detach has been finished,
in the specific case that the ::Detach triggers the deletion
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
With Makefile build, generate_component_general.py was called twice during
build, which did not happen with the ninja build.
This created a race condition with the following error in rare cases:
Traceback (most recent call last):
File "/__w/PX4-Autopilot/PX4-Autopilot/src/lib/component_information/generate_component_general.py", line 79, in <module>
save_compressed(filename)
File "/__w/PX4-Autopilot/PX4-Autopilot/src/lib/component_information/generate_component_general.py", line 33, in save_compressed
with open(filename, 'r') as content_file:
FileNotFoundError: [Errno 2] No such file or directory: '/__w/PX4-Autopilot/PX4-Autopilot/build/px4_sitl_default/component_general.json'
make[3]: *** [src/lib/component_information/CMakeFiles/component_information_header.dir/build.make:68: component_general.json] Error 1
Merging the targets avoids the duplicate execution.
This is to avoid blocking in any case.
If we don't do that, ioctl() may signal data available while the other
protocol does a read(), and when the first protocol tries to do a read(),
it would not have data anymore and would block (so this avoids a race
condition).
Reduces CPU load by almost 1.5% @ 2khz on F4 and F7.
This changes the motor ordering on boards where the timer ordering does
not match the order of the timer usage in the channels defintion.
Only omnibus f4sd is affected.
- move to high priority work queue (from low priority)
- schedule slightly more often to avoid missing messages
- perf counter include all FFT processing work
- lazily allocate gyro gap perf counters on initial sensor selection
There's an increasing amount of slow logged topics at 1-2Hz, which were all
updated in the same logger iteration, leading to data bursts. For log
streaming this started to exceed uart buffer sizes. By distributing updates
more equal over time those bursts are removed, reducing buffer size
requirements.
Tests showed during steady state a reduction of maximum topic updates per
iteration from 40 down to 17.
Also the SD log buffer fill level is more constant.
1. The RTPS IDs are now automatically assigned to the topics
2. Only the topics that get defined to be sent or received in the urtps_bridge_topics.yaml (renamed, since now it doesn't contain IDs) receive the IDs
3. Any addition or removal on the urtps_bridge_topics.yaml file might update the topic IDs - this will require that the agent and the client ID list has to be in sync. This will further require a robustification of the way we check the IDs and the message definitions when starting the bridge.
This allows that all messages (not only timesync messages) that get received on the same system that sent them do not get parsed. As the microRTPS agent is built currently, this will only happen right now if someone sets the same UDP port to send and receive data, or by manually changing the agent topics (which were always autogenerated).
This is an attempt to implement the protocol_splitter with one
read buffer only. The idea is to prevent additional copy
operations from an incoming buffer to the respective protocol buffer.
Right now the benefit is not really there because we are not using a
ringbuffer and have to shift data around quite a bit.
We also try to parse and copy data to the reader immediately without
doing a read from the device which potentially takes 100ms.
We further use a timeout mechanism to prevent starvation if one reader
disconnects and the buffer would fill up from unread data.
A constant large value in the (signed) normalized innovation test ratio is a sign
of bias in the state estimate. This metric can be used to trigger a
covariance boost or reset
Some receivers are initializing to some heading and then resetting to
the correct one after a couple of seconds. EKF2 should detect that and
reset to the new value
The following exception occurs in some rare cases (but only with make build: NO_NINJA_BUILD=1 px4_sitl_default):
Traceback (most recent call last):
File "/__w/PX4-Autopilot/PX4-Autopilot/src/lib/component_information/generate_component_general.py", line 79, in <module>
save_compressed(filename)
File "/__w/PX4-Autopilot/PX4-Autopilot/src/lib/component_information/generate_component_general.py", line 33, in save_compressed
with open(filename, 'r') as content_file:
FileNotFoundError: [Errno 2] No such file or directory: '/__w/PX4-Autopilot/PX4-Autopilot/build/px4_sitl_default/component_general.json'
make[3]: *** [src/lib/component_information/CMakeFiles/component_information_header.dir/build.make:68: component_general.json] Error 1
- naming consistency (estimator prefix as "namespace")
- only publish if baro is available and bias is changing as a small logging optimization
- avoid unnecessary copying (get const reference to status directly)
- trivial code style fixes
This reverts commit 446598d003.
The first warning was due to a race condition that is fixed by the previous commit;
don't omit the first warning anymore
Only modify the _setpoint for takeoff when there is a new uORB message
to avoid a race condition where both vel_sp(2) and accel_sp(2) can be
NAN at the same time.
- this avoids any jitter in the integration timespan from impacting the vibration metrics
- vehicle_imu_status vibration metrics are not consumed by anything
(yet), so changing the scaling of the metric shouldn't matter
This reverts the behavior for offboard velocity setpoint.
Back in v1.11, the velocity input in NED_BODY was assumed to be in the
world frame but rotated by yaw to the vehicle frame. With the current
state the frame is completely fixed to the body. While this might be
technically correct, it doesn't seem much intuitive for multicopters
and breaks the MAVSDK offboard velocity API.
So as an example, with a velocity setpoint of 5 m/s forward, the drone
would in
- v1.11: fly forward with 5 m/s
- v1.12: start to fly forward by pitching down but then descend rapidly
as the forward velocity would translate to a setpoint in Z into the
ground as it is pitched down.
This commit restores the behavior to what we had previously.
2021-07-22 09:40:29 +02:00
1506 changed files with 42112 additions and 31317 deletions
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CBRK*; param show SYS*"' // check that CBRK_BUZZER and SYS_AUTOSTART haven't been lost
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CBRK*; param show SYS*"' // check that CBRK_BUZZER and SYS_AUTOSTART haven't been lost
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CBRK*; param show SYS*"' // check that CBRK_BUZZER and SYS_AUTOSTART haven't been lost
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CBRK*; param show SYS*"' // check that CBRK_BUZZER and SYS_AUTOSTART haven't been lost
}
void printTopics() {
@@ -885,90 +853,127 @@ void printTopics() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb top -1 -a"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener actuator_armed"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener actuator_controls_0"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener actuator_controls_1"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener actuator_controls_2"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener actuator_controls_3"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener actuator_outputs"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener adc_report"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener airspeed_validated"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener airspeed_wind"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener battery_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener commander_state"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener cpuload"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener distance_sensor"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener ekf2_timestamps"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener ekf_gps_drift"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener esc_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_attitude"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_event_flags"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_global_position"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_innovation_test_ratios"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_innovation_variances"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_innovations"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_local_position"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_odometry"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_optical_flow_vel"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_selector_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_sensor_bias"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_states"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_status_flags"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_wind"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener event"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener input_rc"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener led_control"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener log_message"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener logger_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener manual_control_setpoint"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener mavlink_log"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener mission"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener multirotor_motor_limits"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener optical_flow"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener parameter_update"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener position_controller_landing_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener position_setpoint_triplet"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener radio_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener rate_ctrl_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener safety"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_accel"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_accel_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_baro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_combined"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_gyro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_gyro_fft"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_gyro_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_mag"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_preflight_mag"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_selection"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensors_status_imu"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener system_power"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener task_stack_info"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener telemetry_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener test_motor"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener trajectory_setpoint"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener tune_control"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_acceleration"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_air_data"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_angular_acceleration"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_angular_velocity"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_attitude"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_attitude_setpoint"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_command"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_command_ack"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_control_mode"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_global_position"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_imu"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_imu_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_land_detected"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_local_position"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_local_position_setpoint"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_magnetometer"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_odometry"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_rates_setpoint"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_status_flags"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vtol_vehicle_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener yaw_estimator_status"'
// these are for casually inspecting the system, output failure doesn't matter
This repository holds the [PX4](http://px4.io) flight control solution for drones, with the main applications located in the [src/modules](https://github.com/PX4/PX4-Autopilot/tree/master/src/modules) directory. It also contains the PX4 Drone Middleware Platform, which provides drivers and middleware to run drones.
Some files were not shown because too many files have changed in this diff
Show More
Reference in New Issue
Block a user
Blocking a user prevents them from interacting with repositories, such as opening or commenting on pull requests or issues. Learn more about blocking a user.