mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
TIME_ESTIMATE_TO_TARGET: Populate TIME_ESTIMATE_TO_TARGET MAVLink message with the estimated time to RTL
mavlink_messages: Added newly created MAVLink stream mavlink_main: Enabled stream Signed-off-by: marcirsch <marcell@auterion.com>
This commit is contained in:
parent
7f2fea1cca
commit
4bf6ebf4c3
@ -1522,6 +1522,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
configure_stream_local("RC_CHANNELS", 5.0f);
|
||||
configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f);
|
||||
configure_stream_local("SYS_STATUS", 1.0f);
|
||||
configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f);
|
||||
configure_stream_local("UTM_GLOBAL_POSITION", 0.5f);
|
||||
configure_stream_local("VFR_HUD", 4.0f);
|
||||
configure_stream_local("VIBRATION", 0.1f);
|
||||
|
||||
@ -112,6 +112,7 @@
|
||||
#include "streams/STORAGE_INFORMATION.hpp"
|
||||
#include "streams/SYS_STATUS.hpp"
|
||||
#include "streams/SYSTEM_TIME.hpp"
|
||||
#include "streams/TIME_ESTIMATE_TO_TARGET.hpp"
|
||||
#include "streams/TIMESYNC.hpp"
|
||||
#include "streams/TRAJECTORY_REPRESENTATION_WAYPOINTS.hpp"
|
||||
#include "streams/VFR_HUD.hpp"
|
||||
@ -376,6 +377,9 @@ static const StreamListItem streams_list[] = {
|
||||
#if defined(SYSTEM_TIME_HPP)
|
||||
create_stream_list_item<MavlinkStreamSystemTime>(),
|
||||
#endif // SYSTEM_TIME_HPP
|
||||
#if defined(TIME_ESTIMATE_TO_TARGET_HPP)
|
||||
create_stream_list_item<MavlinkStreamTimeEstimateToTarget>(),
|
||||
#endif // TIME_ESTIMATE_TO_TARGET_HPP
|
||||
#if defined(TIMESYNC_HPP)
|
||||
create_stream_list_item<MavlinkStreamTimesync>(),
|
||||
#endif // TIMESYNC_HPP
|
||||
|
||||
78
src/modules/mavlink/streams/TIME_ESTIMATE_TO_TARGET.hpp
Normal file
78
src/modules/mavlink/streams/TIME_ESTIMATE_TO_TARGET.hpp
Normal file
@ -0,0 +1,78 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022 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 TIME_ESTIMATE_TO_TARGET_HPP
|
||||
#define TIME_ESTIMATE_TO_TARGET_HPP
|
||||
|
||||
#include <uORB/topics/rtl_time_estimate.h>
|
||||
|
||||
class MavlinkStreamTimeEstimateToTarget : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamTimeEstimateToTarget(mavlink); }
|
||||
|
||||
static constexpr const char *get_name_static() { return "TIME_ESTIMATE_TO_TARGET"; }
|
||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET; }
|
||||
|
||||
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_TIME_ESTIMATE_TO_TARGET_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
}
|
||||
|
||||
private:
|
||||
explicit MavlinkStreamTimeEstimateToTarget(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
||||
|
||||
uORB::Subscription _rtl_estimate_sub{ORB_ID(rtl_time_estimate)};
|
||||
|
||||
bool send() override
|
||||
{
|
||||
if (_rtl_estimate_sub.updated()) {
|
||||
rtl_time_estimate_s rtl_estimate{};
|
||||
_rtl_estimate_sub.copy(&rtl_estimate);
|
||||
|
||||
mavlink_time_estimate_to_target_t msg{};
|
||||
msg.safe_return = rtl_estimate.safe_time_estimate;
|
||||
|
||||
mavlink_msg_time_estimate_to_target_send_struct(_mavlink->get_channel(), &msg);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // TIME_ESTIMATE_TO_TARGET_HPP
|
||||
Loading…
x
Reference in New Issue
Block a user