mavlink_messages: add GPS_GLOBAL_ORIGIN

sending out local position reference.
Only send as anser to a request message command or
when the origin was changed from externally to verify.
This commit is contained in:
Matthias Grob 2020-11-16 16:38:19 +01:00
parent 41b56f20b8
commit 0ca63120eb
3 changed files with 112 additions and 0 deletions

View File

@ -113,6 +113,7 @@ using matrix::wrap_2pi;
#include "streams/ESC_STATUS.hpp"
#include "streams/EXTENDED_SYS_STATE.hpp"
#include "streams/FLIGHT_INFORMATION.hpp"
#include "streams/GPS_GLOBAL_ORIGIN.hpp"
#include "streams/GPS_STATUS.hpp"
#include "streams/HIGH_LATENCY2.hpp"
#include "streams/HIL_STATE_QUATERNION.hpp"
@ -4301,6 +4302,9 @@ static const StreamListItem streams_list[] = {
create_stream_list_item<MavlinkStreamAttitude>(),
create_stream_list_item<MavlinkStreamAttitudeQuaternion>(),
create_stream_list_item<MavlinkStreamVFRHUD>(),
#if defined(GPS_GLOBAL_ORIGIN_HPP)
create_stream_list_item<MavlinkStreamGpsGlobalOrigin>(),
#endif // GPS_GLOBAL_ORIGIN_HPP
create_stream_list_item<MavlinkStreamGPSRawInt>(),
create_stream_list_item<MavlinkStreamGPS2Raw>(),
create_stream_list_item<MavlinkStreamSystemTime>(),

View File

@ -1229,6 +1229,8 @@ MavlinkReceiver::handle_message_set_gps_global_origin(mavlink_message_t *msg)
(float)origin.altitude * 1.0e-3f, hrt_absolute_time());
_global_ref_timestamp = hrt_absolute_time();
}
handle_request_message_command(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN);
}
void

View File

@ -0,0 +1,106 @@
/****************************************************************************
*
* Copyright (c) 2020 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 GPS_GLOBAL_ORIGIN_HPP
#define GPS_GLOBAL_ORIGIN_HPP
#include <uORB/topics/vehicle_local_position.h>
class MavlinkStreamGpsGlobalOrigin : public MavlinkStream
{
public:
const char *get_name() const override
{
return MavlinkStreamGpsGlobalOrigin::get_name_static();
}
static constexpr const char *get_name_static()
{
return "GPS_GLOBAL_ORIGIN";
}
static constexpr uint16_t get_id_static()
{
return MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
}
uint16_t get_id() override
{
return get_id_static();
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
return new MavlinkStreamGpsGlobalOrigin(mavlink);
}
unsigned get_size() override
{
return _vehicle_local_position_sub.advertised() ?
(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
}
private:
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
/* do not allow top copying this class */
MavlinkStreamGpsGlobalOrigin(MavlinkStreamGpsGlobalOrigin &) = delete;
MavlinkStreamGpsGlobalOrigin &operator = (const MavlinkStreamGpsGlobalOrigin &) = delete;
protected:
explicit MavlinkStreamGpsGlobalOrigin(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
bool send() override
{
vehicle_local_position_s vehicle_local_position;
if (_vehicle_local_position_sub.update(&vehicle_local_position)) {
mavlink_gps_global_origin_t msg{};
if (vehicle_local_position.ref_timestamp > 0) {
msg.latitude = static_cast<int32_t>(vehicle_local_position.ref_lat * 1e7); // double degree -> int32 degreeE7
msg.longitude = static_cast<int32_t>(vehicle_local_position.ref_lon * 1e7); // double degree -> int32 degreeE7
msg.altitude = static_cast<int32_t>(vehicle_local_position.ref_alt * 1e3f); // float m -> int32 mm
msg.time_usec = vehicle_local_position.timestamp; // int64 time since system boot
}
mavlink_msg_gps_global_origin_send_struct(_mavlink->get_channel(), &msg);
return true;
}
return false;
}
};
#endif // GPS_GLOBAL_ORIGIN_HPP