forked from Archive/PX4-Autopilot
MAVLink transmission: Allow faster overall transmissions.
This commit is contained in:
parent
4fb91f47cd
commit
f154f6e5e7
|
@ -3,7 +3,7 @@
|
|||
# USB MAVLink start
|
||||
#
|
||||
|
||||
mavlink start -r 30000 -d /dev/ttyACM0 -x
|
||||
mavlink start -r 80000 -d /dev/ttyACM0 -x
|
||||
# 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 MISSION_ITEM -r 50
|
||||
|
|
|
@ -664,7 +664,7 @@ CONFIG_CDCACM_NWRREQS=4
|
|||
CONFIG_CDCACM_NRDREQS=4
|
||||
CONFIG_CDCACM_BULKIN_REQLEN=96
|
||||
CONFIG_CDCACM_RXBUFSIZE=512
|
||||
CONFIG_CDCACM_TXBUFSIZE=2048
|
||||
CONFIG_CDCACM_TXBUFSIZE=4096
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_PRODUCTID=0x0011
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
|
|
|
@ -90,7 +90,7 @@
|
|||
static const int ERROR = -1;
|
||||
|
||||
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
|
||||
#define MAX_DATA_RATE 60000 ///< max data rate in bytes/s
|
||||
#define MAX_DATA_RATE 1000000 ///< max data rate in bytes/s
|
||||
#define MAIN_LOOP_DELAY 10000 ///< 100 Hz @ 1000 bytes/s data rate
|
||||
#define FLOW_CONTROL_DISABLE_THRESHOLD 40 ///< picked so that some messages still would fit it.
|
||||
|
||||
|
@ -990,7 +990,7 @@ void
|
|||
Mavlink::adjust_stream_rates(const float multiplier)
|
||||
{
|
||||
/* do not allow to push us to zero */
|
||||
if (multiplier < 0.01f) {
|
||||
if (multiplier < 0.0005f) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1001,9 +1001,9 @@ Mavlink::adjust_stream_rates(const float multiplier)
|
|||
unsigned interval = stream->get_interval();
|
||||
interval /= multiplier;
|
||||
|
||||
/* allow max ~600 Hz */
|
||||
/* allow max ~2000 Hz */
|
||||
if (interval < 1600) {
|
||||
interval = 1600;
|
||||
interval = 500;
|
||||
}
|
||||
|
||||
/* set new interval */
|
||||
|
@ -1375,7 +1375,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
|
||||
/* MAVLINK_FTP stream */
|
||||
_mavlink_ftp = (MavlinkFTP *) MavlinkFTP::new_instance(this);
|
||||
_mavlink_ftp->set_interval(interval_from_rate(120.0f));
|
||||
_mavlink_ftp->set_interval(interval_from_rate(1000.0f));
|
||||
LL_APPEND(_streams, _mavlink_ftp);
|
||||
|
||||
/* MISSION_STREAM stream, actually sends all MISSION_XXX messages at some rate depending on
|
||||
|
@ -1425,7 +1425,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
/* set main loop delay depending on data rate to minimize CPU overhead */
|
||||
_main_loop_delay = MAIN_LOOP_DELAY * 1000 / _datarate;
|
||||
_main_loop_delay = (MAIN_LOOP_DELAY * 1000) / _datarate;
|
||||
|
||||
/* now the instance is fully initialized and we can bump the instance count */
|
||||
LL_APPEND(_mavlink_instances, this);
|
||||
|
|
Loading…
Reference in New Issue