mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 14:47:44 +08:00
MAVLink module: Add additional IMUs as default outputs
This simplifies setup and verification of systems, as all three sensors can be looked at in a graph view.
This commit is contained in:
committed by
Daniel Agar
parent
92e9228fcd
commit
4a1d16a06b
@@ -1704,7 +1704,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 10.0f);
|
||||
configure_stream_local("POSITION_TARGET_LOCAL_NED", 10.0f);
|
||||
configure_stream_local("RC_CHANNELS", 20.0f);
|
||||
configure_stream_local("SCALED_IMU", 50.0f);
|
||||
configure_stream_local("SERVO_OUTPUT_RAW_0", 10.0f);
|
||||
configure_stream_local("SYS_STATUS", 5.0f);
|
||||
configure_stream_local("SYSTEM_TIME", 1.0f);
|
||||
@@ -1792,6 +1791,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
configure_stream_local("PING", 1.0f);
|
||||
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 10.0f);
|
||||
configure_stream_local("RC_CHANNELS", 10.0f);
|
||||
configure_stream_local("SCALED_IMU", 25.0f);
|
||||
configure_stream_local("SCALED_IMU2", 25.0f);
|
||||
configure_stream_local("SCALED_IMU3", 25.0f);
|
||||
configure_stream_local("SERVO_OUTPUT_RAW_0", 20.0f);
|
||||
configure_stream_local("SERVO_OUTPUT_RAW_1", 20.0f);
|
||||
configure_stream_local("SYS_STATUS", 1.0f);
|
||||
|
||||
Reference in New Issue
Block a user