mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
uavcan: add OpenDroneID ArmStatus, operator ID
In order to have operator ID be sent by QGC, we need to forward ArmStatus from the remote ID module (here on DroneCAN) to MAVLink.
This commit is contained in:
parent
d999258171
commit
04ea4f9b3a
@ -152,6 +152,8 @@ set(msg_files
|
||||
ObstacleDistance.msg
|
||||
OffboardControlMode.msg
|
||||
OnboardComputerStatus.msg
|
||||
OpenDroneIdArmStatus.msg
|
||||
OpenDroneIdOperatorId.msg
|
||||
OrbitStatus.msg
|
||||
OrbTest.msg
|
||||
OrbTestLarge.msg
|
||||
|
||||
3
msg/OpenDroneIdArmStatus.msg
Normal file
3
msg/OpenDroneIdArmStatus.msg
Normal file
@ -0,0 +1,3 @@
|
||||
uint64 timestamp
|
||||
uint8 status
|
||||
char[50] error
|
||||
4
msg/OpenDroneIdOperatorId.msg
Normal file
4
msg/OpenDroneIdOperatorId.msg
Normal file
@ -0,0 +1,4 @@
|
||||
uint64 timestamp
|
||||
uint8[20] id_or_mac
|
||||
uint8 operator_id_type
|
||||
char[20] operator_id
|
||||
@ -44,7 +44,9 @@ UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) :
|
||||
_node(node),
|
||||
_uavcan_pub_remoteid_basicid(node),
|
||||
_uavcan_pub_remoteid_location(node),
|
||||
_uavcan_pub_remoteid_system(node)
|
||||
_uavcan_pub_remoteid_system(node),
|
||||
_uavcan_pub_remoteid_operator_id(node),
|
||||
_uavcan_sub_arm_status(node)
|
||||
{
|
||||
}
|
||||
|
||||
@ -53,6 +55,14 @@ int UavcanRemoteIDController::init()
|
||||
// Setup timer and call back function for periodic updates
|
||||
_timer.setCallback(TimerCbBinder(this, &UavcanRemoteIDController::periodic_update));
|
||||
_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ));
|
||||
|
||||
int res = _uavcan_sub_arm_status.start(ArmStatusBinder(this, &UavcanRemoteIDController::arm_status_sub_cb));
|
||||
|
||||
if (res < 0) {
|
||||
PX4_WARN("ArmStatus sub failed %i", res);
|
||||
return res;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -63,6 +73,7 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &)
|
||||
send_basic_id();
|
||||
send_location();
|
||||
send_system();
|
||||
send_operator_id();
|
||||
}
|
||||
|
||||
void UavcanRemoteIDController::send_basic_id()
|
||||
@ -254,3 +265,37 @@ void UavcanRemoteIDController::send_system()
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void UavcanRemoteIDController::send_operator_id()
|
||||
{
|
||||
open_drone_id_operator_id_s operator_id;
|
||||
|
||||
if (_open_drone_id_operator_id.copy(&operator_id)) {
|
||||
|
||||
dronecan::remoteid::OperatorID msg {};
|
||||
|
||||
for (unsigned i = 0; i < sizeof(operator_id.id_or_mac); ++i) {
|
||||
msg.id_or_mac.push_back(operator_id.id_or_mac[i]);
|
||||
}
|
||||
|
||||
msg.operator_id_type = operator_id.operator_id_type;
|
||||
|
||||
for (unsigned i = 0; i < sizeof(operator_id.operator_id); ++i) {
|
||||
msg.operator_id.push_back(operator_id.operator_id[i]);
|
||||
}
|
||||
|
||||
_uavcan_pub_remoteid_operator_id.broadcast(msg);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
UavcanRemoteIDController::arm_status_sub_cb(const uavcan::ReceivedDataStructure<dronecan::remoteid::ArmStatus> &msg)
|
||||
{
|
||||
open_drone_id_arm_status_s arm_status{};
|
||||
|
||||
arm_status.timestamp = hrt_absolute_time();
|
||||
arm_status.status = msg.status;
|
||||
memcpy(arm_status.error, msg.error.c_str(), sizeof(arm_status.error));
|
||||
|
||||
_open_drone_id_arm_status_pub.publish(arm_status);
|
||||
}
|
||||
|
||||
@ -33,18 +33,23 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_land_detected.h>
|
||||
#include <uORB/topics/vehicle_air_data.h>
|
||||
#include <uORB/topics/vehicle_local_position.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/open_drone_id_operator_id.h>
|
||||
#include <uORB/topics/open_drone_id_arm_status.h>
|
||||
|
||||
#include <uavcan/uavcan.hpp>
|
||||
#include <dronecan/remoteid/BasicID.hpp>
|
||||
#include <dronecan/remoteid/Location.hpp>
|
||||
#include <dronecan/remoteid/System.hpp>
|
||||
#include <dronecan/remoteid/ArmStatus.hpp>
|
||||
#include <dronecan/remoteid/OperatorID.hpp>
|
||||
|
||||
#include <px4_platform_common/module_params.h>
|
||||
|
||||
@ -68,6 +73,9 @@ private:
|
||||
void send_basic_id();
|
||||
void send_location();
|
||||
void send_system();
|
||||
void send_operator_id();
|
||||
|
||||
void arm_status_sub_cb(const uavcan::ReceivedDataStructure<dronecan::remoteid::ArmStatus> &msg);
|
||||
|
||||
uavcan::INode &_node;
|
||||
|
||||
@ -77,8 +85,16 @@ private:
|
||||
uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)};
|
||||
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
|
||||
uORB::Subscription _home_position_sub{ORB_ID(home_position)};
|
||||
uORB::Subscription _open_drone_id_operator_id{ORB_ID(open_drone_id_operator_id)};
|
||||
uORB::Publication<open_drone_id_arm_status_s> _open_drone_id_arm_status_pub{ORB_ID(open_drone_id_arm_status)};
|
||||
|
||||
uavcan::Publisher<dronecan::remoteid::BasicID> _uavcan_pub_remoteid_basicid;
|
||||
uavcan::Publisher<dronecan::remoteid::Location> _uavcan_pub_remoteid_location;
|
||||
uavcan::Publisher<dronecan::remoteid::System> _uavcan_pub_remoteid_system;
|
||||
uavcan::Publisher<dronecan::remoteid::OperatorID> _uavcan_pub_remoteid_operator_id;
|
||||
|
||||
using ArmStatusBinder = uavcan::MethodBinder < UavcanRemoteIDController *,
|
||||
void (UavcanRemoteIDController::*)(const uavcan::ReceivedDataStructure<dronecan::remoteid::ArmStatus> &) >;
|
||||
|
||||
uavcan::Subscriber<dronecan::remoteid::ArmStatus, ArmStatusBinder> _uavcan_sub_arm_status;
|
||||
};
|
||||
|
||||
@ -1429,6 +1429,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
configure_stream_local("OBSTACLE_DISTANCE", 1.0f);
|
||||
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
|
||||
configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f);
|
||||
configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f);
|
||||
configure_stream_local("ORBIT_EXECUTION_STATUS", 2.0f);
|
||||
configure_stream_local("PING", 0.1f);
|
||||
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.0f);
|
||||
@ -1498,6 +1499,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
|
||||
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
|
||||
configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f);
|
||||
configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f);
|
||||
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
|
||||
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
|
||||
configure_stream_local("PING", 1.0f);
|
||||
@ -1666,6 +1668,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
|
||||
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
|
||||
configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f);
|
||||
configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f);
|
||||
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
|
||||
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
|
||||
configure_stream_local("PING", 1.0f);
|
||||
@ -1758,6 +1761,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f);
|
||||
configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f);
|
||||
configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f);
|
||||
configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f);
|
||||
configure_stream_local("OPTICAL_FLOW_RAD", 1.0f);
|
||||
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
|
||||
configure_stream_local("PING", 0.1f);
|
||||
|
||||
@ -97,6 +97,7 @@
|
||||
#include "streams/OPEN_DRONE_ID_BASIC_ID.hpp"
|
||||
#include "streams/OPEN_DRONE_ID_LOCATION.hpp"
|
||||
#include "streams/OPEN_DRONE_ID_SYSTEM.hpp"
|
||||
#include "streams/OPEN_DRONE_ID_ARM_STATUS.hpp"
|
||||
#include "streams/OPTICAL_FLOW_RAD.hpp"
|
||||
#include "streams/ORBIT_EXECUTION_STATUS.hpp"
|
||||
#include "streams/PING.hpp"
|
||||
@ -457,6 +458,9 @@ static const StreamListItem streams_list[] = {
|
||||
#if defined(OPEN_DRONE_ID_SYSTEM_HPP)
|
||||
create_stream_list_item<MavlinkStreamOpenDroneIdSystem>(),
|
||||
#endif // OPEN_DRONE_ID_SYSTEM_HPP
|
||||
#if defined(OPEN_DRONE_ID_ARM_STATUS_HPP)
|
||||
create_stream_list_item<MavlinkStreamOpenDroneIdArmStatus>(),
|
||||
#endif // OPEN_DRONE_ID_ARM_STATUS_HPP
|
||||
#if defined(ESC_INFO_HPP)
|
||||
create_stream_list_item<MavlinkStreamESCInfo>(),
|
||||
#endif // ESC_INFO_HPP
|
||||
|
||||
@ -280,6 +280,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
|
||||
handle_message_statustext(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID:
|
||||
handle_message_open_drone_id_operator_id(msg);
|
||||
break;
|
||||
|
||||
#if !defined(CONSTRAINED_FLASH)
|
||||
|
||||
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
|
||||
@ -3084,6 +3088,23 @@ MavlinkReceiver::handle_message_gimbal_device_attitude_status(mavlink_message_t
|
||||
_gimbal_device_attitude_status_pub.publish(gimbal_attitude_status);
|
||||
}
|
||||
|
||||
void MavlinkReceiver::handle_message_open_drone_id_operator_id(
|
||||
mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_open_drone_id_operator_id_t odid_module;
|
||||
mavlink_msg_open_drone_id_operator_id_decode(msg, &odid_module);
|
||||
|
||||
open_drone_id_operator_id_s odid_operator_id{};
|
||||
memset(&odid_operator_id, 0, sizeof(odid_operator_id));
|
||||
|
||||
odid_operator_id.timestamp = hrt_absolute_time();
|
||||
memcpy(odid_operator_id.id_or_mac, odid_module.id_or_mac, sizeof(odid_operator_id.id_or_mac));
|
||||
odid_operator_id.operator_id_type = odid_module.operator_id_type;
|
||||
memcpy(odid_operator_id.operator_id, odid_module.operator_id, sizeof(odid_operator_id.operator_id));
|
||||
|
||||
_open_drone_id_operator_id_pub.publish(odid_operator_id);
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkReceiver::run()
|
||||
{
|
||||
|
||||
@ -87,6 +87,7 @@
|
||||
#include <uORB/topics/obstacle_distance.h>
|
||||
#include <uORB/topics/offboard_control_mode.h>
|
||||
#include <uORB/topics/onboard_computer_status.h>
|
||||
#include <uORB/topics/open_drone_id_operator_id.h>
|
||||
#include <uORB/topics/ping.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/radio_status.h>
|
||||
@ -182,6 +183,9 @@ private:
|
||||
void handle_message_obstacle_distance(mavlink_message_t *msg);
|
||||
void handle_message_odometry(mavlink_message_t *msg);
|
||||
void handle_message_onboard_computer_status(mavlink_message_t *msg);
|
||||
void handle_message_open_drone_id_operator_id(mavlink_message_t *msg);
|
||||
void handle_message_open_drone_id_self_id(mavlink_message_t *msg);
|
||||
void handle_message_open_drone_id_system(mavlink_message_t *msg);
|
||||
void handle_message_optical_flow_rad(mavlink_message_t *msg);
|
||||
void handle_message_ping(mavlink_message_t *msg);
|
||||
void handle_message_play_tune(mavlink_message_t *msg);
|
||||
@ -312,6 +316,7 @@ private:
|
||||
uORB::Publication<offboard_control_mode_s> _offboard_control_mode_pub{ORB_ID(offboard_control_mode)};
|
||||
uORB::Publication<onboard_computer_status_s> _onboard_computer_status_pub{ORB_ID(onboard_computer_status)};
|
||||
uORB::Publication<velocity_limits_s> _velocity_limits_pub{ORB_ID(velocity_limits)};
|
||||
uORB::Publication<open_drone_id_operator_id_s> _open_drone_id_operator_id_pub{ORB_ID(open_drone_id_operator_id)};
|
||||
uORB::Publication<generator_status_s> _generator_status_pub{ORB_ID(generator_status)};
|
||||
uORB::Publication<vehicle_attitude_s> _attitude_pub{ORB_ID(vehicle_attitude)};
|
||||
uORB::Publication<vehicle_attitude_setpoint_s> _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)};
|
||||
|
||||
99
src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp
Normal file
99
src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp
Normal file
@ -0,0 +1,99 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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 OPEN_DRONE_ID_ARM_STATUS_HPP
|
||||
#define OPEN_DRONE_ID_ARM_STATUS_HPP
|
||||
|
||||
#include <uORB/topics/open_drone_id_arm_status.h>
|
||||
|
||||
class MavlinkStreamOpenDroneIdArmStatus : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new MavlinkStreamOpenDroneIdArmStatus(mavlink);
|
||||
}
|
||||
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "OPEN_DRONE_ID_ARM_STATUS";
|
||||
}
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS;
|
||||
}
|
||||
|
||||
const char *get_name() const override { return get_name_static(); }
|
||||
uint16_t get_id() override { return get_id_static(); }
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return _open_drone_id_arm_status_sub.advertised()
|
||||
? MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN +
|
||||
MAVLINK_NUM_NON_PAYLOAD_BYTES
|
||||
: 0;
|
||||
}
|
||||
|
||||
private:
|
||||
explicit MavlinkStreamOpenDroneIdArmStatus(Mavlink *mavlink)
|
||||
: MavlinkStream(mavlink) {}
|
||||
|
||||
uORB::Subscription _open_drone_id_arm_status_sub{ORB_ID(open_drone_id_arm_status)};
|
||||
|
||||
bool send() override
|
||||
{
|
||||
open_drone_id_arm_status_s drone_id_arm;
|
||||
|
||||
if (_open_drone_id_arm_status_sub.update(&drone_id_arm)) {
|
||||
|
||||
mavlink_open_drone_id_arm_status_t msg{};
|
||||
|
||||
msg.status = drone_id_arm.status;
|
||||
|
||||
for (uint8_t i = 0; i < sizeof(drone_id_arm.error); ++i) {
|
||||
|
||||
msg.error[i] = drone_id_arm.error[i];
|
||||
|
||||
}
|
||||
|
||||
mavlink_msg_open_drone_id_arm_status_send_struct(_mavlink->get_channel(),
|
||||
&msg);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // OPEN_DRONE_ID_ARM_STATUS_HPP
|
||||
Loading…
x
Reference in New Issue
Block a user