mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 20:28:37 +08:00
feat(msg): add frame field, bump to v1
COMMAND_INT carries a frame field on the wire that determines whether param5/6/7 are AMSL, home-relative, or terrain-relative, but vehicle_command_s had nowhere to put it - so navigator handlers always assumed AMSL. Bump v0 -> v1 with a v0 translation that defaults the new field to FRAME_GLOBAL so external px4_msgs_old consumers keep building. Signed-off-by: Julian Oes <julian@oes.ch>
This commit is contained in:
@@ -18,6 +18,7 @@
|
||||
#include "translation_register_ext_component_request_v1.h"
|
||||
#include "translation_register_ext_component_request_v2.h"
|
||||
#include "translation_vehicle_attitude_setpoint_v1.h"
|
||||
#include "translation_vehicle_command_v1.h"
|
||||
#include "translation_vehicle_command_ack_v1.h"
|
||||
#include "translation_vehicle_local_position_v1.h"
|
||||
#include "translation_vehicle_status_v1.h"
|
||||
|
||||
@@ -0,0 +1,63 @@
|
||||
/****************************************************************************
|
||||
* Copyright (c) 2026 PX4 Development Team.
|
||||
* SPDX-License-Identifier: BSD-3-Clause
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
// Translate VehicleCommand v0 <--> v1
|
||||
#include <px4_msgs_old/msg/vehicle_command_v0.hpp>
|
||||
#include <px4_msgs/msg/vehicle_command.hpp>
|
||||
|
||||
class VehicleCommandV1Translation
|
||||
{
|
||||
public:
|
||||
using MessageOlder = px4_msgs_old::msg::VehicleCommandV0;
|
||||
static_assert(MessageOlder::MESSAGE_VERSION == 0);
|
||||
|
||||
using MessageNewer = px4_msgs::msg::VehicleCommand;
|
||||
static_assert(MessageNewer::MESSAGE_VERSION == 1);
|
||||
|
||||
static constexpr const char *kTopic = "fmu/in/vehicle_command";
|
||||
|
||||
static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer)
|
||||
{
|
||||
msg_newer.timestamp = msg_older.timestamp;
|
||||
msg_newer.param1 = msg_older.param1;
|
||||
msg_newer.param2 = msg_older.param2;
|
||||
msg_newer.param3 = msg_older.param3;
|
||||
msg_newer.param4 = msg_older.param4;
|
||||
msg_newer.param5 = msg_older.param5;
|
||||
msg_newer.param6 = msg_older.param6;
|
||||
msg_newer.param7 = msg_older.param7;
|
||||
msg_newer.frame = MessageNewer::FRAME_GLOBAL; // New field in v1, default to MAV_FRAME_GLOBAL
|
||||
msg_newer.command = msg_older.command;
|
||||
msg_newer.target_system = msg_older.target_system;
|
||||
msg_newer.target_component = msg_older.target_component;
|
||||
msg_newer.source_system = msg_older.source_system;
|
||||
msg_newer.source_component = msg_older.source_component;
|
||||
msg_newer.confirmation = msg_older.confirmation;
|
||||
msg_newer.from_external = msg_older.from_external;
|
||||
}
|
||||
|
||||
static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older)
|
||||
{
|
||||
msg_older.timestamp = msg_newer.timestamp;
|
||||
msg_older.param1 = msg_newer.param1;
|
||||
msg_older.param2 = msg_newer.param2;
|
||||
msg_older.param3 = msg_newer.param3;
|
||||
msg_older.param4 = msg_newer.param4;
|
||||
msg_older.param5 = msg_newer.param5;
|
||||
msg_older.param6 = msg_newer.param6;
|
||||
msg_older.param7 = msg_newer.param7;
|
||||
// Note: frame from v1 is dropped in v0
|
||||
msg_older.command = msg_newer.command;
|
||||
msg_older.target_system = msg_newer.target_system;
|
||||
msg_older.target_component = msg_newer.target_component;
|
||||
msg_older.source_system = msg_newer.source_system;
|
||||
msg_older.source_component = msg_newer.source_component;
|
||||
msg_older.confirmation = msg_newer.confirmation;
|
||||
msg_older.from_external = msg_newer.from_external;
|
||||
}
|
||||
};
|
||||
|
||||
REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleCommandV1Translation);
|
||||
@@ -1,10 +1,19 @@
|
||||
# Vehicle Command uORB message. Used for commanding a mission / action / etc.
|
||||
# Follows the MAVLink COMMAND_INT / COMMAND_LONG definition
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
|
||||
uint64 timestamp # [us] Time since system start.
|
||||
|
||||
# Frame of reference for the lat/lon/alt fields (param5/6/7), mirrors MAV_FRAME.
|
||||
# Only frames relevant to position-bearing commands are listed.
|
||||
uint8 FRAME_GLOBAL = 0 # WGS84 (MSL altitude)
|
||||
uint8 FRAME_GLOBAL_RELATIVE_ALT = 3 # Altitude is relative to home
|
||||
uint8 FRAME_GLOBAL_INT = 5 # Same as FRAME_GLOBAL but coordinates are int32
|
||||
uint8 FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Same as FRAME_GLOBAL_RELATIVE_ALT but int32 coords
|
||||
uint8 FRAME_GLOBAL_TERRAIN_ALT = 10 # Altitude is meters above terrain (AGL)
|
||||
uint8 FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Same as FRAME_GLOBAL_TERRAIN_ALT but int32 coords
|
||||
|
||||
uint16 VEHICLE_CMD_CUSTOM_0 = 0 # Test command.
|
||||
uint16 VEHICLE_CMD_CUSTOM_1 = 1 # Test command.
|
||||
uint16 VEHICLE_CMD_CUSTOM_2 = 2 # Test command.
|
||||
@@ -212,6 +221,7 @@ float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum.
|
||||
float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum.
|
||||
float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum.
|
||||
float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum.
|
||||
uint8 frame # Frame of reference for param5/6/7 (FRAME_* constants above). Defaults to FRAME_GLOBAL when received via COMMAND_LONG which has no frame field.
|
||||
uint32 command # Command ID.
|
||||
uint8 target_system # System which should execute the command.
|
||||
uint8 target_component # Component which should execute the command, 0 for all components.
|
||||
|
||||
Reference in New Issue
Block a user