aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-03-01 19:42:29 +0400
committerAnton Babushkin <anton.babushkin@me.com>2014-03-01 19:42:29 +0400
commita1ea89ea2d3665709f5249ebd7cc3fbadaca603a (patch)
treea04970f0608682c6c4b8934a14325e9c079fa629 /src/modules/mavlink
parent6948defdb26711fd8336b5e0173664bf98517406 (diff)
downloadpx4-firmware-a1ea89ea2d3665709f5249ebd7cc3fbadaca603a.tar.gz
px4-firmware-a1ea89ea2d3665709f5249ebd7cc3fbadaca603a.tar.bz2
px4-firmware-a1ea89ea2d3665709f5249ebd7cc3fbadaca603a.zip
mavlink: more precise message streams timing
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp8
-rw-r--r--src/modules/mavlink/mavlink_rate_limiter.cpp4
-rw-r--r--src/modules/mavlink/mavlink_stream.cpp2
3 files changed, 7 insertions, 7 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index fb29c9c71..e6c474aa7 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -1462,8 +1462,8 @@ MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic)
int
Mavlink::configure_stream(const char *stream_name, const float rate)
{
- /* calculate interval in ms, 0 means disabled stream */
- unsigned int interval = (rate > 0.0f) ? (1000.0f / rate) : 0;
+ /* calculate interval in us, 0 means disabled stream */
+ unsigned int interval = (rate > 0.0f) ? (1000000.0f / rate) : 0;
/* search if stream exists */
MavlinkStream *stream;
@@ -1752,8 +1752,8 @@ Mavlink::task_main(int argc, char *argv[])
/* don't send parameters on startup without request */
_mavlink_param_queue_index = param_count();
- MavlinkRateLimiter slow_rate_limiter(2000.0f / rate_mult);
- MavlinkRateLimiter fast_rate_limiter(100.0f / rate_mult);
+ MavlinkRateLimiter slow_rate_limiter(2000000.0f / rate_mult);
+ MavlinkRateLimiter fast_rate_limiter(100000.0f / rate_mult);
/* set main loop delay depending on data rate to minimize CPU overhead */
_main_loop_delay = MAIN_LOOP_DELAY / rate_mult;
diff --git a/src/modules/mavlink/mavlink_rate_limiter.cpp b/src/modules/mavlink/mavlink_rate_limiter.cpp
index f6ed6e662..9cdda8b17 100644
--- a/src/modules/mavlink/mavlink_rate_limiter.cpp
+++ b/src/modules/mavlink/mavlink_rate_limiter.cpp
@@ -44,7 +44,7 @@ MavlinkRateLimiter::MavlinkRateLimiter() : _last_sent(0), _interval(1000000)
{
}
-MavlinkRateLimiter::MavlinkRateLimiter(unsigned int interval) : _last_sent(0), _interval(interval * 1000)
+MavlinkRateLimiter::MavlinkRateLimiter(unsigned int interval) : _last_sent(0), _interval(interval)
{
}
@@ -55,7 +55,7 @@ MavlinkRateLimiter::~MavlinkRateLimiter()
void
MavlinkRateLimiter::set_interval(unsigned int interval)
{
- _interval = interval * 1000;
+ _interval = interval;
}
bool
diff --git a/src/modules/mavlink/mavlink_stream.cpp b/src/modules/mavlink/mavlink_stream.cpp
index 869495098..bb19d7e33 100644
--- a/src/modules/mavlink/mavlink_stream.cpp
+++ b/src/modules/mavlink/mavlink_stream.cpp
@@ -57,7 +57,7 @@ MavlinkStream::~MavlinkStream()
void
MavlinkStream::set_interval(const unsigned int interval)
{
- _interval = interval * 1000;
+ _interval = interval;
}
/**