|
|
|
@ -90,7 +90,7 @@
@@ -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
@@ -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)
@@ -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[])
@@ -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[])
@@ -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); |
|
|
|
|