mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 14:47:44 +08:00
mavlink: move POSITION_TARGET_GLOBAL_INT to separate streams header
This commit is contained in:
committed by
Lorenz Meier
parent
672a1c90aa
commit
3b20310e9c
@@ -82,11 +82,9 @@
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_land_detected.h>
|
||||
#include <uORB/topics/vehicle_local_position.h>
|
||||
#include <uORB/topics/vehicle_local_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_imu.h>
|
||||
#include <uORB/topics/vehicle_imu_status.h>
|
||||
#include <uORB/topics/vehicle_magnetometer.h>
|
||||
@@ -121,6 +119,7 @@ using matrix::wrap_2pi;
|
||||
#include "streams/OPTICAL_FLOW_RAD.hpp"
|
||||
#include "streams/ORBIT_EXECUTION_STATUS.hpp"
|
||||
#include "streams/PING.hpp"
|
||||
#include "streams/POSITION_TARGET_GLOBAL_INT.hpp"
|
||||
#include "streams/POSITION_TARGET_LOCAL_NED.hpp"
|
||||
#include "streams/PROTOCOL_VERSION.hpp"
|
||||
#include "streams/RAW_RPM.hpp"
|
||||
@@ -3329,102 +3328,6 @@ protected:
|
||||
}
|
||||
};
|
||||
|
||||
class MavlinkStreamPositionTargetGlobalInt : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
const char *get_name() const override
|
||||
{
|
||||
return MavlinkStreamPositionTargetGlobalInt::get_name_static();
|
||||
}
|
||||
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "POSITION_TARGET_GLOBAL_INT";
|
||||
}
|
||||
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
|
||||
}
|
||||
|
||||
uint16_t get_id() override
|
||||
{
|
||||
return get_id_static();
|
||||
}
|
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new MavlinkStreamPositionTargetGlobalInt(mavlink);
|
||||
}
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return _pos_sp_triplet_sub.advertised() ? MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN +
|
||||
MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
|
||||
}
|
||||
|
||||
private:
|
||||
uORB::Subscription _control_mode_sub{ORB_ID(vehicle_control_mode)};
|
||||
uORB::Subscription _lpos_sp_sub{ORB_ID(vehicle_local_position_setpoint)};
|
||||
uORB::Subscription _pos_sp_triplet_sub{ORB_ID(position_setpoint_triplet)};
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamPositionTargetGlobalInt(MavlinkStreamPositionTargetGlobalInt &) = delete;
|
||||
MavlinkStreamPositionTargetGlobalInt &operator = (const MavlinkStreamPositionTargetGlobalInt &) = delete;
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamPositionTargetGlobalInt(Mavlink *mavlink) : MavlinkStream(mavlink)
|
||||
{}
|
||||
|
||||
bool send() override
|
||||
{
|
||||
vehicle_control_mode_s control_mode{};
|
||||
_control_mode_sub.copy(&control_mode);
|
||||
|
||||
if (control_mode.flag_control_position_enabled) {
|
||||
|
||||
position_setpoint_triplet_s pos_sp_triplet{};
|
||||
_pos_sp_triplet_sub.copy(&pos_sp_triplet);
|
||||
|
||||
if (pos_sp_triplet.timestamp > 0 && pos_sp_triplet.current.valid && PX4_ISFINITE(pos_sp_triplet.current.lat)
|
||||
&& PX4_ISFINITE(pos_sp_triplet.current.lon)) {
|
||||
|
||||
mavlink_position_target_global_int_t msg{};
|
||||
|
||||
msg.time_boot_ms = hrt_absolute_time() / 1000;
|
||||
msg.coordinate_frame = MAV_FRAME_GLOBAL_INT;
|
||||
msg.lat_int = pos_sp_triplet.current.lat * 1e7;
|
||||
msg.lon_int = pos_sp_triplet.current.lon * 1e7;
|
||||
msg.alt = pos_sp_triplet.current.alt;
|
||||
|
||||
vehicle_local_position_setpoint_s lpos_sp;
|
||||
|
||||
if (_lpos_sp_sub.copy(&lpos_sp)) {
|
||||
// velocity
|
||||
msg.vx = lpos_sp.vx;
|
||||
msg.vy = lpos_sp.vy;
|
||||
msg.vz = lpos_sp.vz;
|
||||
|
||||
// acceleration
|
||||
msg.afx = lpos_sp.acceleration[0];
|
||||
msg.afy = lpos_sp.acceleration[1];
|
||||
msg.afz = lpos_sp.acceleration[2];
|
||||
|
||||
// yaw
|
||||
msg.yaw = lpos_sp.yaw;
|
||||
msg.yaw_rate = lpos_sp.yawspeed;
|
||||
}
|
||||
|
||||
mavlink_msg_position_target_global_int_send_struct(_mavlink->get_channel(), &msg);
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
class MavlinkStreamCameraCapture : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
@@ -3536,7 +3439,9 @@ static const StreamListItem streams_list[] = {
|
||||
create_stream_list_item<MavlinkStreamServoOutputRaw<0> >(),
|
||||
create_stream_list_item<MavlinkStreamServoOutputRaw<1> >(),
|
||||
create_stream_list_item<MavlinkStreamHILActuatorControls>(),
|
||||
#if defined(POSITION_TARGET_GLOBAL_INT_HPP)
|
||||
create_stream_list_item<MavlinkStreamPositionTargetGlobalInt>(),
|
||||
#endif // POSITION_TARGET_GLOBAL_INT_HPP
|
||||
#if defined(POSITION_TARGET_LOCAL_NED_HPP)
|
||||
create_stream_list_item<MavlinkStreamPositionTargetLocalNed>(),
|
||||
#endif // POSITION_TARGET_LOCAL_NED_HPP
|
||||
|
||||
@@ -34,6 +34,11 @@
|
||||
#ifndef EXTENDED_SYS_STATE_HPP
|
||||
#define EXTENDED_SYS_STATE_HPP
|
||||
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_land_detected.h>
|
||||
|
||||
class MavlinkStreamExtendedSysState : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
|
||||
@@ -0,0 +1,114 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 POSITION_TARGET_GLOBAL_INT_HPP
|
||||
#define POSITION_TARGET_GLOBAL_INT_HPP
|
||||
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/vehicle_local_position_setpoint.h>
|
||||
|
||||
class MavlinkStreamPositionTargetGlobalInt : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamPositionTargetGlobalInt(mavlink); }
|
||||
|
||||
static constexpr const char *get_name_static() { return "POSITION_TARGET_GLOBAL_INT"; }
|
||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; }
|
||||
|
||||
const char *get_name() const override { return get_name_static(); }
|
||||
uint16_t get_id() override { return get_id_static(); }
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return _pos_sp_triplet_sub.advertised() ? MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN +
|
||||
MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
|
||||
}
|
||||
|
||||
private:
|
||||
explicit MavlinkStreamPositionTargetGlobalInt(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
||||
|
||||
uORB::Subscription _control_mode_sub{ORB_ID(vehicle_control_mode)};
|
||||
uORB::Subscription _lpos_sp_sub{ORB_ID(vehicle_local_position_setpoint)};
|
||||
uORB::Subscription _pos_sp_triplet_sub{ORB_ID(position_setpoint_triplet)};
|
||||
|
||||
bool send() override
|
||||
{
|
||||
vehicle_control_mode_s control_mode{};
|
||||
_control_mode_sub.copy(&control_mode);
|
||||
|
||||
if (control_mode.flag_control_position_enabled) {
|
||||
|
||||
position_setpoint_triplet_s pos_sp_triplet{};
|
||||
_pos_sp_triplet_sub.copy(&pos_sp_triplet);
|
||||
|
||||
if (pos_sp_triplet.timestamp > 0 && pos_sp_triplet.current.valid
|
||||
&& PX4_ISFINITE(pos_sp_triplet.current.lat) && PX4_ISFINITE(pos_sp_triplet.current.lon)) {
|
||||
|
||||
mavlink_position_target_global_int_t msg{};
|
||||
|
||||
msg.time_boot_ms = hrt_absolute_time() / 1000;
|
||||
msg.coordinate_frame = MAV_FRAME_GLOBAL_INT;
|
||||
msg.lat_int = pos_sp_triplet.current.lat * 1e7;
|
||||
msg.lon_int = pos_sp_triplet.current.lon * 1e7;
|
||||
msg.alt = pos_sp_triplet.current.alt;
|
||||
|
||||
vehicle_local_position_setpoint_s lpos_sp;
|
||||
|
||||
if (_lpos_sp_sub.copy(&lpos_sp) && (lpos_sp.timestamp > 0)) {
|
||||
// velocity
|
||||
msg.vx = lpos_sp.vx;
|
||||
msg.vy = lpos_sp.vy;
|
||||
msg.vz = lpos_sp.vz;
|
||||
|
||||
// acceleration
|
||||
msg.afx = lpos_sp.acceleration[0];
|
||||
msg.afy = lpos_sp.acceleration[1];
|
||||
msg.afz = lpos_sp.acceleration[2];
|
||||
|
||||
// yaw
|
||||
msg.yaw = lpos_sp.yaw;
|
||||
msg.yaw_rate = lpos_sp.yawspeed;
|
||||
}
|
||||
|
||||
mavlink_msg_position_target_global_int_send_struct(_mavlink->get_channel(), &msg);
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // POSITION_TARGET_GLOBAL_INT_HPP
|
||||
Reference in New Issue
Block a user