/**************************************************************************** * * Copyright (c) 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in * the documentation and/or other materials provided with the * distribution. * 3. Neither the name PX4 nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * ****************************************************************************/ /** * @file mavlink_stream.cpp * Mavlink messages stream implementation. * * @author Anton Babushkin */ #include #include "mavlink_stream.h" #include "mavlink_main.h" MavlinkStream::MavlinkStream(Mavlink *mavlink) : next(nullptr), _mavlink(mavlink), _interval(1000000), _last_sent(0) { } MavlinkStream::~MavlinkStream() { } /** * Set messages interval in ms */ void MavlinkStream::set_interval(const unsigned int interval) { _interval = interval; } /** * Update subscriptions and send message if necessary */ int MavlinkStream::update(const hrt_abstime t) { uint64_t dt = t - _last_sent; unsigned int interval = _interval; if (!const_rate()) { interval /= _mavlink->get_rate_mult(); } if (dt > 0 && dt >= interval) { /* interval expired, send message */ send(t); if (const_rate()) { _last_sent = (t / _interval) * _interval; } else { _last_sent = t; } return 0; } return -1; }