mavlink: more precise message streams timing

This commit is contained in:
Anton Babushkin 2014-03-01 19:42:29 +04:00
parent 6948defdb2
commit a1ea89ea2d
3 changed files with 7 additions and 7 deletions

View File

@ -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;

View File

@ -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

View File

@ -57,7 +57,7 @@ MavlinkStream::~MavlinkStream()
void
MavlinkStream::set_interval(const unsigned int interval)
{
_interval = interval * 1000;
_interval = interval;
}
/**