mavlink: move TIMESYNC to separate stream header

This commit is contained in:
Daniel Agar 2021-02-20 14:01:22 -05:00
parent 849000ebeb
commit 462d67f2b6
2 changed files with 74 additions and 55 deletions

View File

@ -135,6 +135,7 @@ using matrix::wrap_2pi;
#include "streams/STATUSTEXT.hpp"
#include "streams/STORAGE_INFORMATION.hpp"
#include "streams/SYSTEM_TIME.hpp"
#include "streams/TIMESYNC.hpp"
#include "streams/TRAJECTORY_REPRESENTATION_WAYPOINTS.hpp"
#include "streams/VIBRATION.hpp"
#include "streams/WIND_COV.hpp"
@ -1593,61 +1594,6 @@ protected:
};
#endif
class MavlinkStreamTimesync : public MavlinkStream
{
public:
const char *get_name() const override
{
return MavlinkStreamTimesync::get_name_static();
}
static constexpr const char *get_name_static()
{
return "TIMESYNC";
}
static constexpr uint16_t get_id_static()
{
return MAVLINK_MSG_ID_TIMESYNC;
}
uint16_t get_id() override
{
return get_id_static();
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
return new MavlinkStreamTimesync(mavlink);
}
unsigned get_size() override
{
return MAVLINK_MSG_ID_TIMESYNC_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
/* do not allow top copying this class */
MavlinkStreamTimesync(MavlinkStreamTimesync &) = delete;
MavlinkStreamTimesync &operator = (const MavlinkStreamTimesync &) = delete;
protected:
explicit MavlinkStreamTimesync(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
bool send() override
{
mavlink_timesync_t msg{};
msg.tc1 = 0;
msg.ts1 = hrt_absolute_time() * 1000; // boot time in nanoseconds
mavlink_msg_timesync_send_struct(_mavlink->get_channel(), &msg);
return true;
}
};
class MavlinkStreamCameraTrigger : public MavlinkStream
{
public:
@ -1865,7 +1811,9 @@ static const StreamListItem streams_list[] = {
#if defined(SYSTEM_TIME_HPP)
create_stream_list_item<MavlinkStreamSystemTime>(),
#endif // SYSTEM_TIME_HPP
#if defined(TIMESYNC_HPP)
create_stream_list_item<MavlinkStreamTimesync>(),
#endif // TIMESYNC_HPP
#if defined(GLOBAL_POSITION_INT_HPP)
create_stream_list_item<MavlinkStreamGlobalPositionInt>(),
#endif // GLOBAL_POSITION_INT_HPP

View File

@ -0,0 +1,71 @@
/****************************************************************************
*
* Copyright (c) 2021 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.
*
****************************************************************************/
#ifndef TIMESYNC_HPP
#define TIMESYNC_HPP
#include <drivers/drv_hrt.h>
class MavlinkStreamTimesync : public MavlinkStream
{
public:
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamTimesync(mavlink); }
static constexpr const char *get_name_static() { return "TIMESYNC"; }
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_TIMESYNC; }
const char *get_name() const override { return get_name_static(); }
uint16_t get_id() override { return get_id_static(); }
unsigned get_size() override
{
return MAVLINK_MSG_ID_TIMESYNC_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
explicit MavlinkStreamTimesync(Mavlink *mavlink) : MavlinkStream(mavlink) {}
bool send() override
{
mavlink_timesync_t msg{};
msg.tc1 = 0;
msg.ts1 = hrt_absolute_time() * 1000; // boot time in nanoseconds
mavlink_msg_timesync_send_struct(_mavlink->get_channel(), &msg);
return true;
}
};
#endif // TIMESYNC_HPP