mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
mavlink, rc.usb: increase HIL_CONTROLS rate and datarate on USB to allow HIL simulation @ 200Hz
This commit is contained in:
@@ -3,7 +3,7 @@
|
|||||||
# USB MAVLink start
|
# USB MAVLink start
|
||||||
#
|
#
|
||||||
|
|
||||||
mavlink start -r 10000 -d /dev/ttyACM0 -x
|
mavlink start -r 20000 -d /dev/ttyACM0 -x
|
||||||
# Enable a number of interesting streams we want via USB
|
# Enable a number of interesting streams we want via USB
|
||||||
mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 200
|
mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 200
|
||||||
usleep 100000
|
usleep 100000
|
||||||
|
|||||||
@@ -90,7 +90,7 @@
|
|||||||
static const int ERROR = -1;
|
static const int ERROR = -1;
|
||||||
|
|
||||||
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
|
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
|
||||||
#define MAX_DATA_RATE 10000 // max data rate in bytes/s
|
#define MAX_DATA_RATE 20000 // max data rate in bytes/s
|
||||||
#define MAIN_LOOP_DELAY 10000 // 100 Hz @ 1000 bytes/s data rate
|
#define MAIN_LOOP_DELAY 10000 // 100 Hz @ 1000 bytes/s data rate
|
||||||
|
|
||||||
#define TX_BUFFER_GAP MAVLINK_MAX_PACKET_LEN
|
#define TX_BUFFER_GAP MAVLINK_MAX_PACKET_LEN
|
||||||
@@ -694,7 +694,7 @@ Mavlink::set_hil_enabled(bool hil_enabled)
|
|||||||
/* enable HIL */
|
/* enable HIL */
|
||||||
if (hil_enabled && !_hil_enabled) {
|
if (hil_enabled && !_hil_enabled) {
|
||||||
_hil_enabled = true;
|
_hil_enabled = true;
|
||||||
configure_stream("HIL_CONTROLS", 150.0f);
|
configure_stream("HIL_CONTROLS", 200.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* disable HIL */
|
/* disable HIL */
|
||||||
|
|||||||
Reference in New Issue
Block a user