forked from Archive/PX4-Autopilot
microRTPS: simplify the attribution of the RTPS IDs by makiing it automatic
1. The RTPS IDs are now automatically assigned to the topics 2. Only the topics that get defined to be sent or received in the urtps_bridge_topics.yaml (renamed, since now it doesn't contain IDs) receive the IDs 3. Any addition or removal on the urtps_bridge_topics.yaml file might update the topic IDs - this will require that the agent and the client ID list has to be in sync. This will further require a robustification of the way we check the IDs and the message definitions when starting the bridge.
This commit is contained in:
parent
f557fbc99f
commit
c478e2985a
|
@ -323,7 +323,7 @@ pipeline {
|
|||
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
|
||||
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_ros_com.git -b ${BRANCH_NAME}")
|
||||
// deploy uORB RTPS ID map
|
||||
sh('./msg/tools/uorb_to_ros_rtps_ids.py -i msg/tools/uorb_rtps_message_ids.yaml -o px4_ros_com/templates/uorb_rtps_message_ids.yaml')
|
||||
sh('./msg/tools/uorb_to_ros_rtps_ids.py -i msg/tools/urtps_bridge_topics.yaml -o px4_ros_com/templates/urtps_bridge_topics.yaml')
|
||||
sh('cd px4_ros_com; git status; git add .; git commit -a -m "Update uORB RTPS ID map `date`" || true')
|
||||
sh('cd px4_ros_com; git push origin ${BRANCH_NAME} || true')
|
||||
// deploy uORB RTPS required tools
|
||||
|
|
|
@ -15,7 +15,6 @@ import os
|
|||
|
||||
import genmsg.msgs
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
|
||||
topic_names = [s.short_name for s in spec]
|
||||
|
@ -153,7 +152,7 @@ void *send(void *args)
|
|||
// copy raw data into local buffer. Payload is shifted by header length to make room for header
|
||||
serialize_@(send_base_types[idx])(&writer, &@(topic)_data, &data_buffer[header_length], &length);
|
||||
|
||||
if (0 < (read = transport_node->write(static_cast<char>(@(rtps_message_id(ids, topic))), data_buffer, length))) {
|
||||
if (0 < (read = transport_node->write(static_cast<char>(@(ids[0].index(topic) + 1)), data_buffer, length))) {
|
||||
data->total_sent += read;
|
||||
tx_last_sec_read += read;
|
||||
++data->sent;
|
||||
|
@ -262,7 +261,7 @@ void micrortps_start_topics(const uint32_t &datarate, struct timespec &begin, ui
|
|||
|
||||
switch (topic_ID) {
|
||||
@[ for idx, topic in enumerate(recv_topics)]@
|
||||
case @(rtps_message_id(ids, topic)): {
|
||||
case @(ids[0].index(topic) + 1): {
|
||||
@(receive_base_types[idx])_s @(topic)_data;
|
||||
deserialize_@(receive_base_types[idx])(&reader, &@(topic)_data, data_buffer);
|
||||
|
||||
|
|
|
@ -11,12 +11,10 @@
|
|||
@# - ids (List) list of all RTPS msg ids
|
||||
@###############################################
|
||||
@{
|
||||
from packaging import version
|
||||
import genmsg.msgs
|
||||
from packaging import version
|
||||
import re
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
topic = alias if alias else spec.short_name
|
||||
|
||||
try:
|
||||
|
|
|
@ -11,10 +11,9 @@
|
|||
@# - ids (List) list of all RTPS msg ids
|
||||
@###############################################
|
||||
@{
|
||||
from packaging import version
|
||||
import genmsg.msgs
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from packaging import version
|
||||
import re
|
||||
|
||||
topic = alias if alias else spec.short_name
|
||||
try:
|
||||
|
|
|
@ -10,11 +10,8 @@
|
|||
@# - ids (List) list of all RTPS msg ids
|
||||
@###############################################
|
||||
@{
|
||||
import os
|
||||
|
||||
import genmsg.msgs
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
import os
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
|
||||
send_topics = [(alias[idx] if alias[idx] else s.short_name) for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND]
|
||||
|
@ -64,7 +61,7 @@ bool RtpsTopics::init(std::condition_variable *t_send_queue_cv, std::mutex *t_se
|
|||
std::cout << "\033[0;36m--- Subscribers ---\033[0m" << std::endl;
|
||||
@[for topic in recv_topics]@
|
||||
|
||||
if (_@(topic)_sub.init(@(rtps_message_id(ids, topic)), t_send_queue_cv, t_send_queue_mutex, t_send_queue, ns)) {
|
||||
if (_@(topic)_sub.init(@(ids[0].index(topic) + 1), t_send_queue_cv, t_send_queue_mutex, t_send_queue, ns)) {
|
||||
std::cout << "- @(topic) subscriber started" << std::endl;
|
||||
|
||||
} else {
|
||||
|
@ -76,6 +73,7 @@ bool RtpsTopics::init(std::condition_variable *t_send_queue_cv, std::mutex *t_se
|
|||
std::cout << "\033[0;36m-----------------------\033[0m" << std::endl << std::endl;
|
||||
@[end if]@
|
||||
@[if send_topics]@
|
||||
|
||||
// Initialise publishers
|
||||
std::cout << "\033[0;36m---- Publishers ----\033[0m" << std::endl;
|
||||
@[for topic in send_topics]@
|
||||
|
@ -107,28 +105,32 @@ bool RtpsTopics::init(std::condition_variable *t_send_queue_cv, std::mutex *t_se
|
|||
}
|
||||
|
||||
@[if send_topics]@
|
||||
template <typename T>
|
||||
void RtpsTopics::sync_timestamp_of_incoming_data(T &msg) {
|
||||
uint64_t timestamp = getMsgTimestamp(&msg);
|
||||
uint64_t timestamp_sample = getMsgTimestampSample(&msg);
|
||||
_timesync->subtractOffset(timestamp);
|
||||
setMsgTimestamp(&msg, timestamp);
|
||||
_timesync->subtractOffset(timestamp_sample);
|
||||
setMsgTimestampSample(&msg, timestamp_sample);
|
||||
}
|
||||
|
||||
void RtpsTopics::publish(const uint8_t topic_ID, char data_buffer[], size_t len)
|
||||
{
|
||||
switch (topic_ID) {
|
||||
@[for topic in send_topics]@
|
||||
|
||||
case @(rtps_message_id(ids, topic)): { // @(topic)
|
||||
case @(ids[0].index(topic) + 1): { // @(topic) publisher
|
||||
@(topic)_msg_t st;
|
||||
eprosima::fastcdr::FastBuffer cdrbuffer(data_buffer, len);
|
||||
eprosima::fastcdr::Cdr cdr_des(cdrbuffer);
|
||||
st.deserialize(cdr_des);
|
||||
|
||||
@[ if topic == 'Timesync' or topic == 'timesync']@
|
||||
_timesync->processTimesyncMsg(&st, &_@(topic)_pub);
|
||||
@[ end if]@
|
||||
|
||||
// apply timestamp offset
|
||||
uint64_t timestamp = getMsgTimestamp(&st);
|
||||
uint64_t timestamp_sample = getMsgTimestampSample(&st);
|
||||
_timesync->subtractOffset(timestamp);
|
||||
setMsgTimestamp(&st, timestamp);
|
||||
_timesync->subtractOffset(timestamp_sample);
|
||||
setMsgTimestampSample(&st, timestamp_sample);
|
||||
sync_timestamp_of_incoming_data(st);
|
||||
|
||||
_@(topic)_pub.publish(&st);
|
||||
}
|
||||
|
@ -143,6 +145,15 @@ void RtpsTopics::publish(const uint8_t topic_ID, char data_buffer[], size_t len)
|
|||
}
|
||||
@[end if]@
|
||||
@[if recv_topics]@
|
||||
template <typename T>
|
||||
void RtpsTopics::sync_timestamp_of_outgoing_data(T &msg) {
|
||||
uint64_t timestamp = getMsgTimestamp(&msg);
|
||||
uint64_t timestamp_sample = getMsgTimestampSample(&msg);
|
||||
_timesync->addOffset(timestamp);
|
||||
setMsgTimestamp(&msg, timestamp);
|
||||
_timesync->addOffset(timestamp_sample);
|
||||
setMsgTimestampSample(&msg, timestamp_sample);
|
||||
}
|
||||
|
||||
bool RtpsTopics::getMsg(const uint8_t topic_ID, eprosima::fastcdr::Cdr &scdr)
|
||||
{
|
||||
|
@ -151,17 +162,12 @@ bool RtpsTopics::getMsg(const uint8_t topic_ID, eprosima::fastcdr::Cdr &scdr)
|
|||
switch (topic_ID) {
|
||||
@[for topic in recv_topics]@
|
||||
|
||||
case @(rtps_message_id(ids, topic)): // @(topic)
|
||||
case @(ids[0].index(topic) + 1): // @(topic) subscriber
|
||||
if (_@(topic)_sub.hasMsg()) {
|
||||
@(topic)_msg_t msg = _@(topic)_sub.getMsg();
|
||||
|
||||
// apply timestamps offset
|
||||
uint64_t timestamp = getMsgTimestamp(&msg);
|
||||
uint64_t timestamp_sample = getMsgTimestampSample(&msg);
|
||||
_timesync->addOffset(timestamp);
|
||||
setMsgTimestamp(&msg, timestamp);
|
||||
_timesync->addOffset(timestamp_sample);
|
||||
setMsgTimestampSample(&msg, timestamp_sample);
|
||||
// apply timestamp offset
|
||||
sync_timestamp_of_outgoing_data(msg);
|
||||
|
||||
msg.serialize(scdr);
|
||||
ret = true;
|
||||
|
|
|
@ -10,12 +10,9 @@
|
|||
@# - ids (List) list of all RTPS msg ids
|
||||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import os
|
||||
from packaging import version
|
||||
|
||||
import genmsg.msgs
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
|
||||
send_topics = [(alias[idx] if alias[idx] else s.short_name) for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND]
|
||||
|
@ -98,9 +95,13 @@ public:
|
|||
const std::string &ns);
|
||||
void set_timesync(const std::shared_ptr<TimeSync> ×ync) { _timesync = timesync; };
|
||||
@[if send_topics]@
|
||||
template <typename T>
|
||||
void sync_timestamp_of_incoming_data(T &msg);
|
||||
void publish(const uint8_t topic_ID, char data_buffer[], size_t len);
|
||||
@[end if]@
|
||||
@[if recv_topics]@
|
||||
template <typename T>
|
||||
void sync_timestamp_of_outgoing_data(T &msg);
|
||||
bool getMsg(const uint8_t topic_ID, eprosima::fastcdr::Cdr &scdr);
|
||||
@[end if]@
|
||||
|
||||
|
|
|
@ -11,12 +11,10 @@
|
|||
@# - ids (List) list of all RTPS msg ids
|
||||
@###############################################
|
||||
@{
|
||||
from packaging import version
|
||||
import genmsg.msgs
|
||||
from packaging import version
|
||||
import re
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
topic = alias if alias else spec.short_name
|
||||
try:
|
||||
ros2_distro = ros2_distro.decode("utf-8")
|
||||
|
|
|
@ -11,10 +11,9 @@
|
|||
@# - ids (List) list of all RTPS msg ids
|
||||
@###############################################
|
||||
@{
|
||||
from packaging import version
|
||||
import genmsg.msgs
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from packaging import version
|
||||
import re
|
||||
|
||||
topic = alias if alias else spec.short_name
|
||||
try:
|
||||
|
|
|
@ -12,8 +12,6 @@
|
|||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
|
||||
try:
|
||||
|
|
|
@ -12,8 +12,6 @@
|
|||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
|
||||
package = package[0]
|
||||
|
|
|
@ -11,10 +11,8 @@
|
|||
@# - ids (List) list of all RTPS msg ids
|
||||
@###############################################
|
||||
@{
|
||||
from packaging import version
|
||||
import genmsg.msgs
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from packaging import version
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
|
||||
package = package[0]
|
||||
|
|
|
@ -37,9 +37,8 @@
|
|||
@#
|
||||
@################################################################################
|
||||
@{
|
||||
from packaging import version
|
||||
import genmsg.msgs
|
||||
|
||||
from packaging import version
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
builtin_types = set()
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
################################################################################
|
||||
#
|
||||
# Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||||
# Copyright (c) 2018-2019 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2018-2021 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:
|
||||
|
@ -42,7 +42,6 @@ import os
|
|||
import argparse
|
||||
import shutil
|
||||
import px_generate_uorb_topic_files
|
||||
import px_generate_uorb_topic_helper
|
||||
from uorb_rtps_classifier import Classifier
|
||||
import subprocess
|
||||
import glob
|
||||
|
@ -70,81 +69,11 @@ except ImportError as e:
|
|||
sys.exit(1)
|
||||
|
||||
|
||||
def check_rtps_id_uniqueness(classifier):
|
||||
"""
|
||||
Checks if there are no ID's for different msgs repeated on the map
|
||||
"""
|
||||
|
||||
repeated_ids = dict()
|
||||
|
||||
full_send_list = dict(list(msg for msg in list(classifier.msgs_to_send.items(
|
||||
))) + list(list(msg[0].items())[0] for msg in classifier.alias_msgs_to_send))
|
||||
full_receive_list = dict(list(msg for msg in list(classifier.msgs_to_receive.items(
|
||||
))) + list(list(msg[0].items())[0] for msg in classifier.alias_msgs_to_receive))
|
||||
full_ignore_list = dict(list(msg for msg in list(classifier.msgs_to_ignore.items(
|
||||
))) + list(list(msg[0].items())[0] for msg in classifier.alias_msgs_to_ignore))
|
||||
|
||||
# check if there are repeated ID's on the messages to send
|
||||
for key, value in list(full_send_list.items()):
|
||||
if list(full_send_list.values()).count(value) > 1:
|
||||
repeated_ids.update({key: value})
|
||||
|
||||
# check if there are repeated ID's on the messages to receive
|
||||
for key, value in list(full_receive_list.items()):
|
||||
if list(full_receive_list.values()).count(value) > 1:
|
||||
repeated_ids.update({key: value})
|
||||
|
||||
# check if there are repeated ID's on the messages to ignore
|
||||
for key, value in list(full_ignore_list.items()):
|
||||
if list(full_ignore_list.values()).count(value) > 1:
|
||||
repeated_ids.update({key: value})
|
||||
|
||||
# check if there are repeated IDs between classified and unclassified msgs
|
||||
# check send and ignore lists
|
||||
send_ignore_common_ids = list(set(full_ignore_list.values(
|
||||
)).intersection(list(full_send_list.values())))
|
||||
for item in list(full_send_list.items()):
|
||||
for repeated in send_ignore_common_ids:
|
||||
if item[1] == repeated:
|
||||
repeated_ids.update({item[0]: item[1]})
|
||||
for item in list(full_ignore_list.items()):
|
||||
for repeated in send_ignore_common_ids:
|
||||
if item[1] == repeated:
|
||||
repeated_ids.update({item[0]: item[1]})
|
||||
|
||||
# check receive and ignore lists
|
||||
receive_ignore_common_ids = list(set(full_ignore_list.values(
|
||||
)).intersection(list(full_receive_list.values())))
|
||||
for item in list(full_receive_list.items()):
|
||||
for repeated in receive_ignore_common_ids:
|
||||
if item[1] == repeated:
|
||||
repeated_ids.update({item[0]: item[1]})
|
||||
for item in list(full_ignore_list.items()):
|
||||
for repeated in receive_ignore_common_ids:
|
||||
if item[1] == repeated:
|
||||
repeated_ids.update({item[0]: item[1]})
|
||||
|
||||
all_msgs = {}
|
||||
all_msgs.update(full_send_list)
|
||||
all_msgs.update(full_receive_list)
|
||||
all_msgs.update(full_ignore_list)
|
||||
all_ids = list()
|
||||
all_ids = list(all_msgs.values())
|
||||
all_ids.sort()
|
||||
|
||||
if not repeated_ids:
|
||||
print("All good. RTPS ID's are unique")
|
||||
else:
|
||||
raise AssertionError(", ".join('%s' % msgs for msgs in list(repeated_ids.keys())) +
|
||||
" have their ID's repeated. Please choose from the following pool:\n" +
|
||||
", ".join('%d' % id for id in px_generate_uorb_topic_helper.check_available_ids(all_ids)))
|
||||
|
||||
|
||||
default_client_out = "src/modules/micrortps_bridge/micrortps_client"
|
||||
default_agent_out = "src/modules/micrortps_bridge/micrortps_agent"
|
||||
default_uorb_templates_dir = "templates/uorb_microcdr"
|
||||
default_urtps_templates_dir = "templates/urtps"
|
||||
default_rtps_id_file = "tools/uorb_rtps_message_ids.yaml"
|
||||
default_urtps_topics_file = "tools/urtps_bridge_topics.yaml"
|
||||
default_package_name = px_generate_uorb_topic_files.PACKAGE
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
|
@ -168,7 +97,7 @@ parser.add_argument("-b", "--uorb-templates-dir", dest='uorb_templates', type=st
|
|||
parser.add_argument("-q", "--urtps-templates-dir", dest='urtps_templates', type=str,
|
||||
help="uRTPS templates, by default using relative path to msgdir 'templates/urtps'", default=default_urtps_templates_dir)
|
||||
parser.add_argument("-y", "--rtps-ids-file", dest='yaml_file', type=str,
|
||||
help="RTPS msg IDs definition path, by default using relative path to msgdir 'tools/uorb_rtps_message_ids.yaml'", default=default_rtps_id_file)
|
||||
help="Setup uRTPS bridge topics file path, by default using relative path to msgdir 'tools/urtps_bridge_topics.yaml'", default=default_urtps_topics_file)
|
||||
parser.add_argument("-p", "--package", dest='package', type=str,
|
||||
help="Msg package naming, by default px4", default=default_package_name)
|
||||
parser.add_argument("-o", "--agent-outdir", dest='agentdir', type=str,
|
||||
|
@ -319,13 +248,10 @@ uorb_templates_dir = (args.uorb_templates if os.path.isabs(args.uorb_templates)
|
|||
urtps_templates_dir = (args.urtps_templates if os.path.isabs(args.urtps_templates)
|
||||
else os.path.join(msg_dir, args.urtps_templates))
|
||||
|
||||
# parse yaml file into a map of ids
|
||||
# parse yaml file into a map of ids and messages to send and receive
|
||||
classifier = (Classifier(os.path.abspath(args.yaml_file), msg_dir) if os.path.isabs(args.yaml_file)
|
||||
else Classifier(os.path.join(msg_dir, args.yaml_file), msg_dir))
|
||||
|
||||
# check if there are no ID's repeated
|
||||
check_rtps_id_uniqueness(classifier)
|
||||
|
||||
|
||||
uRTPS_CLIENT_TEMPL_FILE = 'microRTPS_client.cpp.em'
|
||||
uRTPS_AGENT_TOPICS_H_TEMPL_FILE = 'RtpsTopics.h.em'
|
||||
|
@ -359,7 +285,7 @@ def generate_agent(out_dir):
|
|||
|
||||
if classifier.alias_msgs_to_send:
|
||||
for msg_file in classifier.alias_msgs_to_send:
|
||||
msg_alias = list(msg_file[0].keys())[0]
|
||||
msg_alias = msg_file[0]
|
||||
msg_name = msg_file[1]
|
||||
if gen_idl:
|
||||
if out_dir != agent_out_dir:
|
||||
|
@ -389,7 +315,7 @@ def generate_agent(out_dir):
|
|||
|
||||
if classifier.alias_msgs_to_receive:
|
||||
for msg_file in classifier.alias_msgs_to_receive:
|
||||
msg_alias = list(msg_file[0].keys())[0]
|
||||
msg_alias = msg_file[0]
|
||||
msg_name = msg_file[1]
|
||||
if gen_idl:
|
||||
if out_dir != agent_out_dir:
|
||||
|
|
|
@ -218,10 +218,10 @@ def generate_uRTPS_general(filename_send_msgs, filename_alias_send_msgs, filenam
|
|||
for msg in filename_receive_msgs)
|
||||
|
||||
alias_send_msgs = list([os.path.join(
|
||||
msg_dir, msg[1] + ".msg"), list(msg[0].keys())[0]] for msg in filename_alias_send_msgs)
|
||||
msg_dir, msg[1] + ".msg"), msg[0]] for msg in filename_alias_send_msgs)
|
||||
|
||||
alias_receive_msgs = list([os.path.join(
|
||||
msg_dir, msg[1] + ".msg"), list(msg[0].keys())[0]] for msg in filename_alias_receive_msgs)
|
||||
msg_dir, msg[1] + ".msg"), msg[0]] for msg in filename_alias_receive_msgs)
|
||||
|
||||
em_globals_list = []
|
||||
if send_msgs:
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#!/usr/bin/env python3
|
||||
#############################################################################
|
||||
#
|
||||
# Copyright (C) 2013-2019 PX4 Pro Development Team. All rights reserved.
|
||||
# Copyright (C) 2013-2021 PX4 Pro Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
|
@ -296,9 +296,10 @@ def print_field(field):
|
|||
if field.name == 'timestamp':
|
||||
print(("if (message.timestamp != 0) {\n\t\tPX4_INFO_RAW(\"\\t" + field.name +
|
||||
": " + c_type + " (%.6f seconds ago)\\n\", " + field_name +
|
||||
", (now - message.timestamp) / 1e6);\n\t} else {\n\t\tPX4_INFO_RAW(\"\\n\");\n\t}"))
|
||||
", (now - message.timestamp) / 1e6);\n\t} else {\n\t\tPX4_INFO_RAW(\"\\n\");\n\t}"))
|
||||
elif field.name == 'timestamp_sample':
|
||||
print(("\n\tPX4_INFO_RAW(\"\\t" + field.name + ": " + c_type + " (" + c_type + " us before timestamp)\\n\", " + field_name + ", message.timestamp - message.timestamp_sample);\n\t"))
|
||||
print(("\n\tPX4_INFO_RAW(\"\\t" + field.name + ": " + c_type + " (" + c_type +
|
||||
" us before timestamp)\\n\", " + field_name + ", message.timestamp - message.timestamp_sample);\n\t"))
|
||||
elif field.name == 'device_id':
|
||||
print("char device_id_buffer[80];")
|
||||
print("device::Device::device_id_print_buffer(device_id_buffer, sizeof(device_id_buffer), message.device_id);")
|
||||
|
@ -322,19 +323,25 @@ def print_field(field):
|
|||
elif (field.name == 'q' or 'q_' in field.name) and field.type == 'float32[4]':
|
||||
# float32[4] q/q_d/q_reset/delta_q_reset
|
||||
print("{")
|
||||
print("\t\tmatrix::Eulerf euler{matrix::Quatf{message." + field.name + "}};")
|
||||
print("\t\tPX4_INFO_RAW(\"\\t" + field.name + ": " + c_type + " (Roll: %.1f deg, Pitch: %.1f deg, Yaw: %.1f deg" ")\\n\", " + field_name + ", (double)math::degrees(euler(0)), (double)math::degrees(euler(1)), (double)math::degrees(euler(2)));\n\t")
|
||||
print(
|
||||
"\t\tmatrix::Eulerf euler{matrix::Quatf{message." + field.name + "}};")
|
||||
print("\t\tPX4_INFO_RAW(\"\\t" + field.name + ": " + c_type + " (Roll: %.1f deg, Pitch: %.1f deg, Yaw: %.1f deg" ")\\n\", " +
|
||||
field_name + ", (double)math::degrees(euler(0)), (double)math::degrees(euler(1)), (double)math::degrees(euler(2)));\n\t")
|
||||
print("\t}")
|
||||
|
||||
elif ("flags" in field.name or "bits" in field.name) and "uint" in field.type:
|
||||
# print bits of fixed width unsigned integers (uint8, uint16, uint32) if name contains flags or bits
|
||||
print("PX4_INFO_RAW(\"\\t" + field.name + ": " + c_type + " (0b\", " + field_name + ");")
|
||||
print("\tfor (int i = (sizeof(" + field_name + ") * 8) - 1; i >= 0; i--) { PX4_INFO_RAW(\"%lu%s\", (unsigned long) " + field_name + " >> i & 1, ((unsigned)i < (sizeof(" + field_name + ") * 8) - 1 && i % 4 == 0 && i > 0) ? \"'\" : \"\"); }")
|
||||
print("PX4_INFO_RAW(\"\\t" + field.name + ": " +
|
||||
c_type + " (0b\", " + field_name + ");")
|
||||
print("\tfor (int i = (sizeof(" + field_name + ") * 8) - 1; i >= 0; i--) { PX4_INFO_RAW(\"%lu%s\", (unsigned long) "
|
||||
+ field_name + " >> i & 1, ((unsigned)i < (sizeof(" + field_name + ") * 8) - 1 && i % 4 == 0 && i > 0) ? \"'\" : \"\"); }")
|
||||
print("\tPX4_INFO_RAW(\")\\n\");")
|
||||
elif is_array and 'char' in field.type:
|
||||
print(("PX4_INFO_RAW(\"\\t" + field.name + ": \\\"%." + str(array_length) + "s\\\" \\n\", message." + field.name + ");"))
|
||||
print(("PX4_INFO_RAW(\"\\t" + field.name + ": \\\"%." +
|
||||
str(array_length) + "s\\\" \\n\", message." + field.name + ");"))
|
||||
else:
|
||||
print(("PX4_INFO_RAW(\"\\t" + field.name + ": " + c_type + "\\n\", " + field_name + ");"))
|
||||
print(("PX4_INFO_RAW(\"\\t" + field.name + ": " +
|
||||
c_type + "\\n\", " + field_name + ");"))
|
||||
|
||||
|
||||
def print_field_def(field):
|
||||
|
@ -375,37 +382,4 @@ def print_field_def(field):
|
|||
comment = ' // required for logger'
|
||||
|
||||
print(('\t%s%s%s %s%s;%s' % (type_prefix, type_px4, type_appendix, field.name,
|
||||
array_size, comment)))
|
||||
|
||||
|
||||
def check_available_ids(used_msg_ids_list):
|
||||
"""
|
||||
Checks the available RTPS ID's
|
||||
"""
|
||||
return set(list(range(0, 255))) - set(used_msg_ids_list)
|
||||
|
||||
|
||||
def rtps_message_id(msg_id_map, message):
|
||||
"""
|
||||
Get RTPS ID of uORB message
|
||||
"""
|
||||
error_msg = ""
|
||||
|
||||
# check if the message has an ID set
|
||||
for dict in msg_id_map[0]['rtps']:
|
||||
if message in dict['msg']:
|
||||
if dict['id'] is not None:
|
||||
return dict['id']
|
||||
else:
|
||||
error_msg = "ID is None!"
|
||||
break
|
||||
|
||||
# create list of the available IDs if it fails to get an ID
|
||||
used_ids = list()
|
||||
for dict in msg_id_map[0]['rtps']:
|
||||
if dict['id'] is not None:
|
||||
used_ids.append(dict['id'])
|
||||
|
||||
raise AssertionError(
|
||||
"%s %s Please add an ID from the available pool:\n" % (message, error_msg) +
|
||||
", ".join('%d' % id for id in check_available_ids(used_ids)))
|
||||
array_size, comment)))
|
||||
|
|
|
@ -31,143 +31,79 @@
|
|||
#
|
||||
################################################################################
|
||||
|
||||
import sys
|
||||
import os
|
||||
import argparse
|
||||
import errno
|
||||
import yaml
|
||||
import re
|
||||
import difflib
|
||||
import errno
|
||||
import os
|
||||
from typing import Dict, List, Tuple
|
||||
import yaml
|
||||
|
||||
|
||||
class Classifier():
|
||||
"""
|
||||
Class to classify RTPS msgs as senders, receivers or to be ignored
|
||||
"""
|
||||
"""Class to classify RTPS msgs as to send, receive and set their IDs."""
|
||||
|
||||
def __init__(self, yaml_file, msg_folder):
|
||||
def __init__(self, yaml_file, msg_folder) -> None:
|
||||
self.msg_folder = msg_folder
|
||||
self.all_msgs_list = self.set_all_msgs()
|
||||
self.msg_id_map = self.parse_yaml_msg_id_file(yaml_file)
|
||||
self.alias_space_init_id = 180
|
||||
self.msg_map = self.parse_yaml_msgs_file(yaml_file)
|
||||
|
||||
# Checkers
|
||||
self.check_if_listed(yaml_file)
|
||||
# Check if base types are defined correctly
|
||||
self.check_base_type()
|
||||
self.check_id_space()
|
||||
|
||||
self.msgs_to_send, self.alias_msgs_to_send = self.set_msgs_to_send()
|
||||
self.msgs_to_receive, self.alias_msgs_to_receive = self.set_msgs_to_receive()
|
||||
self.msgs_to_ignore, self.alias_msgs_to_ignore = self.set_msgs_to_ignore()
|
||||
# Get messages to send and to receive
|
||||
self.msgs_to_send: Dict[str, int] = dict()
|
||||
self.msgs_to_receive: Dict[str, int] = dict()
|
||||
self.alias_msgs_to_send: List[Tuple[str, str]] = []
|
||||
self.alias_msgs_to_receive: List[Tuple[str, str]] = []
|
||||
self.msg_id_map: List[str] = []
|
||||
|
||||
# Create message map
|
||||
self.setup_msg_map()
|
||||
|
||||
self.msg_files_send = self.set_msg_files_send()
|
||||
self.msg_files_receive = self.set_msg_files_receive()
|
||||
self.msg_files_ignore = self.set_msg_files_ignore()
|
||||
|
||||
# setters (for class init)
|
||||
def set_all_msgs(self):
|
||||
msg_list = []
|
||||
for filename in os.listdir(self.msg_folder):
|
||||
if '.msg' in filename:
|
||||
# add base messages
|
||||
msg_list.append(re.sub(".msg", "", filename))
|
||||
|
||||
# add alias / multi-topics messages
|
||||
with open(os.path.join(self.msg_folder, filename), 'r') as f:
|
||||
alias_msgs = []
|
||||
lines = f.readlines()
|
||||
for line in lines:
|
||||
if '# TOPICS' in line:
|
||||
fileUpdated = True
|
||||
alias_msgs += line.split()
|
||||
alias_msgs.remove('#')
|
||||
alias_msgs.remove('TOPICS')
|
||||
for msg in alias_msgs:
|
||||
if msg not in msg_list:
|
||||
msg_list.append(msg)
|
||||
return msg_list
|
||||
|
||||
def set_msgs_to_send(self):
|
||||
send = {}
|
||||
send_alias = []
|
||||
for dict in self.msg_id_map['rtps']:
|
||||
if 'send' in list(dict.keys()):
|
||||
if 'alias' in list(dict.keys()):
|
||||
send_alias.append(
|
||||
({dict['msg']: dict['id']}, dict['alias']))
|
||||
def setup_msg_map(self) -> None:
|
||||
"""Setup dictionary with an ID map for the messages."""
|
||||
for topic in self.msg_map['rtps']:
|
||||
if 'send' in list(topic.keys()):
|
||||
if 'base' in list(topic.keys()):
|
||||
self.alias_msgs_to_send.append(
|
||||
(topic['msg'], topic['base']))
|
||||
else:
|
||||
send.update({dict['msg']: dict['id']})
|
||||
return send, send_alias
|
||||
|
||||
def set_msgs_to_receive(self):
|
||||
receive = {}
|
||||
receive_alias = []
|
||||
for dict in self.msg_id_map['rtps']:
|
||||
if 'receive' in list(dict.keys()):
|
||||
if 'alias' in list(dict.keys()):
|
||||
receive_alias.append(
|
||||
({dict['msg']: dict['id']}, dict['alias']))
|
||||
self.msgs_to_send.update({topic['msg']: 0})
|
||||
if 'receive' in list(topic.keys()):
|
||||
if 'base' in list(topic.keys()):
|
||||
self.alias_msgs_to_receive.append(
|
||||
(topic['msg'], topic['base']))
|
||||
else:
|
||||
receive.update({dict['msg']: dict['id']})
|
||||
return receive, receive_alias
|
||||
self.msgs_to_receive.update({topic['msg']: 0})
|
||||
self.msg_id_map.append(topic['msg'])
|
||||
|
||||
def set_msgs_to_ignore(self):
|
||||
ignore = {}
|
||||
ignore_alias = []
|
||||
for dict in self.msg_id_map['rtps']:
|
||||
if (('send' not in list(dict.keys())) and ('receive' not in list(dict.keys()))):
|
||||
if 'alias' in list(dict.keys()):
|
||||
ignore_alias.append(
|
||||
({dict['msg']: dict['id']}, dict['alias']))
|
||||
else:
|
||||
ignore.update({dict['msg']: dict['id']})
|
||||
return ignore, ignore_alias
|
||||
|
||||
def set_msg_files_send(self):
|
||||
def set_msg_files_send(self) -> list:
|
||||
"""
|
||||
Append the path to the files which messages are marked to
|
||||
be sent.
|
||||
"""
|
||||
return [os.path.join(self.msg_folder, msg + ".msg")
|
||||
for msg in list(self.msgs_to_send.keys())]
|
||||
|
||||
def set_msg_files_receive(self):
|
||||
def set_msg_files_receive(self) -> list:
|
||||
"""
|
||||
Append the path to the files which messages are marked to
|
||||
be received.
|
||||
"""
|
||||
return [os.path.join(self.msg_folder, msg + ".msg")
|
||||
for msg in list(self.msgs_to_receive.keys())]
|
||||
|
||||
def set_msg_files_ignore(self):
|
||||
return [os.path.join(self.msg_folder, msg + ".msg")
|
||||
for msg in list(self.msgs_to_ignore.keys())]
|
||||
|
||||
def check_if_listed(self, yaml_file):
|
||||
"""
|
||||
Checks if all msgs are listed under the RTPS ID yaml file
|
||||
"""
|
||||
none_listed_msgs = []
|
||||
for msg in self.all_msgs_list:
|
||||
result = not any(
|
||||
dict['msg'] == msg for dict in self.msg_id_map['rtps'])
|
||||
if result:
|
||||
none_listed_msgs.append(msg)
|
||||
|
||||
if len(none_listed_msgs) > 0:
|
||||
if len(none_listed_msgs) == 1:
|
||||
error_msg = "The following message is not listen under "
|
||||
elif len(none_listed_msgs) > 1:
|
||||
error_msg = "The following messages are not listen under "
|
||||
|
||||
raise AssertionError(
|
||||
"\n%s %s: " % (error_msg, yaml_file) + ", ".join('%s' % msg for msg in none_listed_msgs) +
|
||||
"\n\nPlease add them to the yaml file with the respective ID and, if applicable, mark them " +
|
||||
"to be sent or received by the micro-RTPS bridge.\n"
|
||||
"NOTE: If the message is an alias / part of multi-topics (#TOPICS) of a base message, it should be added as well.\n")
|
||||
|
||||
def check_base_type(self):
|
||||
"""
|
||||
Check if alias message has correct base type
|
||||
"""
|
||||
def check_base_type(self) -> None:
|
||||
"""Check if alias message has correct base type."""
|
||||
registered_alias_msgs = list(
|
||||
dict['alias'] for dict in self.msg_id_map['rtps'] if 'alias' in list(dict.keys()))
|
||||
topic['base'] for topic in self.msg_map['rtps'] if 'base' in list(topic.keys()))
|
||||
|
||||
base_types = []
|
||||
for dict in self.msg_id_map['rtps']:
|
||||
if 'alias' not in list(dict.keys()):
|
||||
base_types.append(dict['msg'])
|
||||
for topic in self.msg_map['rtps']:
|
||||
if 'base' not in list(topic.keys()):
|
||||
base_types.append(topic['msg'])
|
||||
|
||||
incorrect_base_types = list(
|
||||
set(registered_alias_msgs) - set(base_types))
|
||||
|
@ -181,40 +117,17 @@ class Classifier():
|
|||
raise AssertionError(
|
||||
('\n' + '\n'.join('\t- The multi-topic message base type \'{}\' does not exist.{}'.format(k, (' Did you mean \'' + v[0] + '\'?' if v else '')) for k, v in list(base_types_suggestion.items()))))
|
||||
|
||||
def check_id_space(self):
|
||||
"""
|
||||
Check if msg ID is in the correct ID space
|
||||
"""
|
||||
incorrect_base_ids = {}
|
||||
incorrect_alias_ids = {}
|
||||
for dict in self.msg_id_map['rtps']:
|
||||
if 'alias' not in list(dict.keys()) and dict['id'] >= self.alias_space_init_id:
|
||||
incorrect_base_ids.update({dict['msg']: dict['id']})
|
||||
elif 'alias' in list(dict.keys()) and dict['id'] < self.alias_space_init_id:
|
||||
incorrect_alias_ids.update({dict['msg']: dict['id']})
|
||||
|
||||
if len(incorrect_base_ids) > 0:
|
||||
raise AssertionError(
|
||||
('\n' + '\n'.join('\t- The message \'{} with ID \'{}\' is in the wrong ID space. Please use any of the available IDs from 0 to 169'.format(k, v) for k, v in list(incorrect_base_ids.items()))))
|
||||
|
||||
if len(incorrect_alias_ids) > 0:
|
||||
raise AssertionError(
|
||||
('\n' + '\n'.join('\t- The alias message \'{}\' with ID \'{}\' is in the wrong ID space. Please use any of the available IDs from 170 to 255'.format(k, v) for k, v in list(incorrect_alias_ids.items()))))
|
||||
|
||||
@staticmethod
|
||||
def parse_yaml_msg_id_file(yaml_file):
|
||||
"""
|
||||
Parses a yaml file into a dict
|
||||
"""
|
||||
def parse_yaml_msgs_file(yaml_file) -> dict:
|
||||
"""Parses a yaml file into a dict."""
|
||||
try:
|
||||
with open(yaml_file, 'r') as f:
|
||||
return yaml.safe_load(f)
|
||||
except OSError as e:
|
||||
if e.errno == errno.ENOENT:
|
||||
with open(yaml_file, 'r') as file:
|
||||
return yaml.safe_load(file)
|
||||
except OSError as err:
|
||||
if err.errno == errno.ENOENT:
|
||||
raise IOError(errno.ENOENT, os.strerror(
|
||||
errno.ENOENT), yaml_file)
|
||||
else:
|
||||
raise
|
||||
raise
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
|
@ -233,8 +146,8 @@ if __name__ == "__main__":
|
|||
parser.add_argument("-m", "--topic-msg-dir", dest='msgdir', type=str,
|
||||
help="Topics message dir, by default msg/", default="msg")
|
||||
parser.add_argument("-y", "--rtps-ids-file", dest='yaml_file', type=str,
|
||||
help="RTPS msg IDs definition file absolute path, by default use relative path to msg, tools/uorb_rtps_message_ids.yaml",
|
||||
default='tools/uorb_rtps_message_ids.yaml')
|
||||
help="RTPS msg IDs definition file absolute path, by default use relative path to msg, tools/urtps_bridge_topics.yaml",
|
||||
default='tools/urtps_bridge_topics.yaml')
|
||||
|
||||
# Parse arguments
|
||||
args = parser.parse_args()
|
||||
|
@ -250,36 +163,24 @@ if __name__ == "__main__":
|
|||
if args.send:
|
||||
if args.path:
|
||||
print(('send files: ' + ', '.join(str(msg_file)
|
||||
for msg_file in classifier.msgs_files_send) + '\n'))
|
||||
for msg_file in classifier.msg_files_send) + '\n'))
|
||||
else:
|
||||
if args.alias:
|
||||
print((', '.join(str(msg)
|
||||
for msg in list(classifier.msgs_to_send.keys())) + (' alias ' + ', '.join(str(list(msg[0].keys())[0])
|
||||
for msg in classifier.alias_msgs_to_send) if len(classifier.alias_msgs_to_send) > 0 else '') + '\n'))
|
||||
for msg in sorted(classifier.msgs_to_send)) + (' alias ' + ', '.join(msg[0]
|
||||
for msg in classifier.alias_msgs_to_send) if len(classifier.alias_msgs_to_send) > 0 else '') + '\n'))
|
||||
else:
|
||||
print((', '.join(str(msg)
|
||||
for msg in list(classifier.msgs_to_send.keys()))))
|
||||
for msg in sorted(classifier.msgs_to_send))))
|
||||
if args.receive:
|
||||
if args.path:
|
||||
print(('receive files: ' + ', '.join(str(msg_file)
|
||||
for msg_file in classifier.msgs_files_receive) + '\n'))
|
||||
for msg_file in classifier.msg_files_receive) + '\n'))
|
||||
else:
|
||||
if args.alias:
|
||||
print((', '.join(str(msg)
|
||||
for msg in list(classifier.msgs_to_receive.keys())) + (' alias ' + ', '.join(str(list(msg[0].keys())[0])
|
||||
for msg in classifier.alias_msgs_to_receive) if len(classifier.alias_msgs_to_receive) > 0 else '') + '\n'))
|
||||
for msg in sorted(classifier.msgs_to_receive)) + (' alias ' + ', '.join(msg[0]
|
||||
for msg in classifier.alias_msgs_to_receive) if len(classifier.alias_msgs_to_receive) > 0 else '') + '\n'))
|
||||
else:
|
||||
print((', '.join(str(msg)
|
||||
for msg in list(classifier.msgs_to_receive.keys()))))
|
||||
if args.ignore:
|
||||
if args.path:
|
||||
print(('ignore files: ' + ', '.join(str(msg_file)
|
||||
for msg_file in classifier.msgs_files_ignore) + '\n'))
|
||||
else:
|
||||
if args.alias:
|
||||
print((', '.join(str(msg)
|
||||
for msg in list(classifier.msgs_to_ignore.keys())) + (' alias ' + ', '.join(str(list(msg[0].keys())[0])
|
||||
for msg in classifier.alias_msgs_to_ignore) if len(classifier.alias_msgs_to_ignore) > 0 else '') + '\n'))
|
||||
else:
|
||||
print((', '.join(str(msg)
|
||||
for msg in list(classifier.msgs_to_ignore.keys()))))
|
||||
for msg in sorted(classifier.msgs_to_receive))))
|
||||
|
|
|
@ -1,460 +0,0 @@
|
|||
rtps:
|
||||
- msg: actuator_armed
|
||||
id: 0
|
||||
- msg: actuator_controls
|
||||
id: 1
|
||||
- msg: actuator_outputs
|
||||
id: 3
|
||||
- msg: adc_report
|
||||
id: 4
|
||||
- msg: airspeed
|
||||
id: 5
|
||||
- msg: battery_status
|
||||
id: 6
|
||||
- msg: camera_capture
|
||||
id: 7
|
||||
- msg: camera_trigger
|
||||
id: 8
|
||||
- msg: collision_report
|
||||
id: 9
|
||||
- msg: commander_state
|
||||
id: 10
|
||||
- msg: cpuload
|
||||
id: 11
|
||||
- msg: debug_array
|
||||
id: 12
|
||||
receive: true
|
||||
- msg: debug_key_value
|
||||
id: 13
|
||||
receive: true
|
||||
- msg: debug_value
|
||||
id: 14
|
||||
receive: true
|
||||
- msg: debug_vect
|
||||
id: 15
|
||||
receive: true
|
||||
- msg: differential_pressure
|
||||
id: 16
|
||||
- msg: distance_sensor
|
||||
id: 17
|
||||
- msg: estimator_innovations
|
||||
id: 18
|
||||
- msg: ekf2_timestamps
|
||||
id: 19
|
||||
- msg: ekf_gps_drift
|
||||
id: 20
|
||||
- msg: sensor_gps
|
||||
id: 21
|
||||
- msg: esc_report
|
||||
id: 22
|
||||
- msg: esc_status
|
||||
id: 23
|
||||
- msg: estimator_status
|
||||
id: 24
|
||||
- msg: follow_target
|
||||
id: 25
|
||||
- msg: geofence_result
|
||||
id: 26
|
||||
- msg: gps_dump
|
||||
id: 27
|
||||
- msg: gps_inject_data
|
||||
id: 28
|
||||
- msg: home_position
|
||||
id: 29
|
||||
- msg: input_rc
|
||||
id: 30
|
||||
send: true
|
||||
- msg: iridiumsbd_status
|
||||
id: 31
|
||||
- msg: irlock_report
|
||||
id: 32
|
||||
- msg: landing_target_innovations
|
||||
id: 33
|
||||
- msg: landing_target_pose
|
||||
id: 34
|
||||
- msg: led_control
|
||||
id: 35
|
||||
- msg: log_message
|
||||
id: 36
|
||||
- msg: manual_control_setpoint
|
||||
id: 37
|
||||
- msg: mavlink_log
|
||||
id: 38
|
||||
- msg: mission
|
||||
id: 39
|
||||
- msg: mission_result
|
||||
id: 40
|
||||
- msg: mount_orientation
|
||||
id: 41
|
||||
- msg: multirotor_motor_limits
|
||||
id: 42
|
||||
- msg: obstacle_distance
|
||||
id: 43
|
||||
- msg: offboard_control_mode
|
||||
id: 44
|
||||
receive: true
|
||||
- msg: optical_flow
|
||||
id: 45
|
||||
receive: true
|
||||
- msg: parameter_update
|
||||
id: 46
|
||||
- msg: ping
|
||||
id: 47
|
||||
- msg: position_controller_landing_status
|
||||
id: 48
|
||||
- msg: position_controller_status
|
||||
id: 49
|
||||
- msg: position_setpoint
|
||||
id: 50
|
||||
receive: true
|
||||
- msg: position_setpoint_triplet
|
||||
id: 51
|
||||
receive: true
|
||||
- msg: power_button_state
|
||||
id: 52
|
||||
- msg: pwm_input
|
||||
id: 53
|
||||
- msg: qshell_req
|
||||
id: 54
|
||||
- msg: qshell_retval
|
||||
id: 55
|
||||
- msg: radio_status
|
||||
id: 56
|
||||
- msg: rate_ctrl_status
|
||||
id: 57
|
||||
- msg: rc_channels
|
||||
id: 58
|
||||
- msg: rc_parameter_map
|
||||
id: 59
|
||||
- msg: safety
|
||||
id: 60
|
||||
- msg: satellite_info
|
||||
id: 61
|
||||
send: true
|
||||
- msg: sensor_accel
|
||||
id: 62
|
||||
- msg: sensor_baro
|
||||
id: 63
|
||||
- msg: estimator_sensor_bias
|
||||
id: 64
|
||||
- msg: sensor_combined
|
||||
id: 65
|
||||
send: true
|
||||
- msg: sensor_correction
|
||||
id: 66
|
||||
- msg: sensor_gyro
|
||||
id: 67
|
||||
- msg: sensor_mag
|
||||
id: 68
|
||||
- msg: sensors_status_imu
|
||||
id: 69
|
||||
- msg: sensor_selection
|
||||
id: 70
|
||||
- msg: px4io_status
|
||||
id: 71
|
||||
- msg: system_power
|
||||
id: 73
|
||||
- msg: task_stack_info
|
||||
id: 74
|
||||
- msg: tecs_status
|
||||
id: 75
|
||||
- msg: telemetry_status
|
||||
id: 76
|
||||
receive: true
|
||||
- msg: test_motor
|
||||
id: 77
|
||||
- msg: timesync
|
||||
id: 78
|
||||
receive: true
|
||||
send: true
|
||||
- msg: trajectory_waypoint
|
||||
id: 79
|
||||
send: true
|
||||
- msg: transponder_report
|
||||
id: 80
|
||||
- msg: tune_control
|
||||
id: 81
|
||||
- msg: uavcan_parameter_request
|
||||
id: 82
|
||||
- msg: uavcan_parameter_value
|
||||
id: 83
|
||||
- msg: ulog_stream
|
||||
id: 84
|
||||
- msg: ulog_stream_ack
|
||||
id: 85
|
||||
- msg: vehicle_air_data
|
||||
id: 86
|
||||
- msg: vehicle_attitude
|
||||
id: 87
|
||||
send: true
|
||||
- msg: vehicle_attitude_setpoint
|
||||
id: 88
|
||||
- msg: vehicle_command
|
||||
id: 89
|
||||
receive: true
|
||||
- msg: vehicle_command_ack
|
||||
id: 90
|
||||
- msg: vehicle_constraints
|
||||
id: 91
|
||||
- msg: vehicle_control_mode
|
||||
id: 92
|
||||
send: true
|
||||
- msg: vehicle_global_position
|
||||
id: 93
|
||||
- msg: vehicle_gps_position
|
||||
id: 94
|
||||
- msg: vehicle_land_detected
|
||||
id: 95
|
||||
- msg: vehicle_local_position
|
||||
id: 96
|
||||
send: true
|
||||
- msg: vehicle_local_position_setpoint
|
||||
id: 97
|
||||
receive: true
|
||||
- msg: vehicle_magnetometer
|
||||
id: 98
|
||||
- msg: vehicle_odometry
|
||||
id: 99
|
||||
send: true
|
||||
- msg: vehicle_rates_setpoint
|
||||
id: 100
|
||||
- msg: vehicle_roi
|
||||
id: 101
|
||||
- msg: vehicle_status
|
||||
id: 102
|
||||
send: true
|
||||
- msg: vehicle_status_flags
|
||||
id: 103
|
||||
- msg: vehicle_trajectory_waypoint
|
||||
id: 104
|
||||
receive: true
|
||||
- msg: vtol_vehicle_status
|
||||
id: 105
|
||||
- msg: wind
|
||||
id: 106
|
||||
- msg: collision_constraints
|
||||
id: 107
|
||||
send: true
|
||||
- msg: orbit_status
|
||||
id: 108
|
||||
- msg: power_monitor
|
||||
id: 109
|
||||
- msg: landing_gear
|
||||
id: 110
|
||||
- msg: wheel_encoders
|
||||
id: 111
|
||||
- msg: vehicle_angular_velocity
|
||||
id: 112
|
||||
send: true
|
||||
- msg: vehicle_acceleration
|
||||
id: 113
|
||||
- msg: airspeed_validated
|
||||
id: 115
|
||||
- msg: onboard_computer_status
|
||||
id: 116
|
||||
receive: true
|
||||
- msg: cellular_status
|
||||
id: 117
|
||||
- msg: sensor_accel_fifo
|
||||
id: 118
|
||||
- msg: sensor_gyro_fifo
|
||||
id: 119
|
||||
- msg: vehicle_imu
|
||||
id: 120
|
||||
- msg: vehicle_imu_status
|
||||
id: 121
|
||||
- msg: vehicle_angular_acceleration
|
||||
id: 122
|
||||
- msg: logger_status
|
||||
id: 123
|
||||
- msg: rpm
|
||||
id: 124
|
||||
- msg: hover_thrust_estimate
|
||||
id: 125
|
||||
- msg: trajectory_bezier
|
||||
id: 126
|
||||
receive: true
|
||||
- msg: vehicle_trajectory_bezier
|
||||
id: 127
|
||||
receive: true
|
||||
- msg: timesync_status
|
||||
id: 128
|
||||
send: true
|
||||
- msg: orb_test
|
||||
id: 129
|
||||
- msg: orb_test_medium
|
||||
id: 130
|
||||
- msg: orb_test_large
|
||||
id: 131
|
||||
- msg: yaw_estimator_status
|
||||
id: 132
|
||||
- msg: sensor_preflight_mag
|
||||
id: 133
|
||||
- msg: estimator_states
|
||||
id: 134
|
||||
- msg: generator_status
|
||||
id: 135
|
||||
- msg: sensor_gyro_fft
|
||||
id: 136
|
||||
- msg: navigator_mission_item
|
||||
id: 137
|
||||
- msg: estimator_optical_flow_vel
|
||||
id: 138
|
||||
- msg: estimator_selector_status
|
||||
id: 139
|
||||
- msg: manual_control_switches
|
||||
id: 140
|
||||
- msg: estimator_status_flags
|
||||
id: 141
|
||||
- msg: rtl_flight_time
|
||||
id: 142
|
||||
- msg: vehicle_angular_acceleration_setpoint
|
||||
id: 143
|
||||
- msg: vehicle_torque_setpoint
|
||||
id: 144
|
||||
- msg: vehicle_thrust_setpoint
|
||||
id: 145
|
||||
- msg: vehicle_actuator_setpoint
|
||||
id: 146
|
||||
- msg: control_allocator_status
|
||||
id: 147
|
||||
- msg: mag_worker_data
|
||||
id: 148
|
||||
- msg: takeoff_status
|
||||
id: 149
|
||||
- msg: heater_status
|
||||
id: 150
|
||||
- msg: gimbal_device_attitude_status
|
||||
id: 151
|
||||
- msg: gimbal_device_information
|
||||
id: 152
|
||||
- msg: gimbal_device_set_attitude
|
||||
id: 153
|
||||
- msg: gimbal_manager_information
|
||||
id: 154
|
||||
- msg: gimbal_manager_set_attitude
|
||||
id: 155
|
||||
- msg: gimbal_manager_status
|
||||
id: 156
|
||||
- msg: gimbal_manager_set_manual_control
|
||||
id: 157
|
||||
- msg: airspeed_wind
|
||||
id: 158
|
||||
- msg: estimator_event_flags
|
||||
id: 159
|
||||
- msg: event
|
||||
id: 160
|
||||
- msg: estimator_baro_bias
|
||||
id: 161
|
||||
- msg: internal_combustion_engine_status
|
||||
id: 162
|
||||
- msg: camera_status
|
||||
id: 163
|
||||
########## multi topics: begin ##########
|
||||
- msg: actuator_controls_0
|
||||
id: 180
|
||||
alias: actuator_controls
|
||||
- msg: actuator_controls_1
|
||||
id: 181
|
||||
alias: actuator_controls
|
||||
- msg: actuator_controls_2
|
||||
id: 182
|
||||
alias: actuator_controls
|
||||
- msg: actuator_controls_3
|
||||
id: 183
|
||||
alias: actuator_controls
|
||||
- msg: actuator_controls_virtual_fw
|
||||
id: 184
|
||||
alias: actuator_controls
|
||||
- msg: actuator_controls_virtual_mc
|
||||
id: 185
|
||||
alias: actuator_controls
|
||||
- msg: mc_virtual_attitude_setpoint
|
||||
id: 186
|
||||
alias: vehicle_attitude_setpoint
|
||||
- msg: fw_virtual_attitude_setpoint
|
||||
id: 187
|
||||
alias: vehicle_attitude_setpoint
|
||||
- msg: vehicle_attitude_groundtruth
|
||||
id: 188
|
||||
alias: vehicle_attitude
|
||||
- msg: vehicle_global_position_groundtruth
|
||||
id: 189
|
||||
alias: vehicle_global_position
|
||||
- msg: vehicle_local_position_groundtruth
|
||||
id: 190
|
||||
alias: vehicle_local_position
|
||||
- msg: vehicle_mocap_odometry
|
||||
alias: vehicle_odometry
|
||||
id: 191
|
||||
receive: true
|
||||
- msg: vehicle_visual_odometry
|
||||
id: 192
|
||||
alias: vehicle_odometry
|
||||
receive: true
|
||||
- msg: vehicle_trajectory_waypoint_desired
|
||||
id: 193
|
||||
alias: vehicle_trajectory_waypoint
|
||||
send: true
|
||||
- msg: obstacle_distance_fused
|
||||
id: 194
|
||||
alias: obstacle_distance
|
||||
- msg: vehicle_vision_attitude
|
||||
id: 195
|
||||
alias: vehicle_attitude
|
||||
- msg: trajectory_setpoint
|
||||
id: 196
|
||||
alias: vehicle_local_position_setpoint
|
||||
receive: true
|
||||
- msg: camera_trigger_secondary
|
||||
id: 197
|
||||
alias: camera_trigger
|
||||
- msg: vehicle_angular_velocity_groundtruth
|
||||
id: 198
|
||||
alias: vehicle_angular_velocity
|
||||
- msg: estimator_visual_odometry_aligned
|
||||
id: 199
|
||||
alias: vehicle_odometry
|
||||
- msg: estimator_innovation_variances
|
||||
id: 200
|
||||
alias: estimator_innovations
|
||||
- msg: estimator_innovation_test_ratios
|
||||
id: 201
|
||||
alias: estimator_innovations
|
||||
- msg: orb_multitest
|
||||
id: 202
|
||||
alias: orb_test
|
||||
- msg: orb_test_medium_multi
|
||||
id: 203
|
||||
alias: orb_test_medium
|
||||
- msg: orb_test_medium_queue
|
||||
id: 204
|
||||
alias: orb_test_medium
|
||||
- msg: orb_test_medium_queue_poll
|
||||
id: 205
|
||||
alias: orb_test_medium
|
||||
- msg: orb_test_medium_wrap_around
|
||||
id: 206
|
||||
alias: orb_test_medium
|
||||
- msg: estimator_local_position
|
||||
id: 207
|
||||
alias: vehicle_local_position
|
||||
- msg: estimator_global_position
|
||||
id: 208
|
||||
alias: vehicle_global_position
|
||||
- msg: estimator_attitude
|
||||
id: 209
|
||||
alias: vehicle_attitude
|
||||
- msg: estimator_odometry
|
||||
id: 210
|
||||
alias: vehicle_odometry
|
||||
- msg: actuator_controls_4
|
||||
id: 211
|
||||
alias: actuator_controls
|
||||
- msg: actuator_controls_5
|
||||
id: 212
|
||||
alias: actuator_controls
|
||||
- msg: estimator_wind
|
||||
id: 213
|
||||
alias: wind
|
||||
########## multi topics: end ##########
|
|
@ -0,0 +1,89 @@
|
|||
#####
|
||||
#
|
||||
# This file maps all the topics that are to be used on the microRTPS bridge.
|
||||
# When one wants to add a new topic to the bridge, it should add it to this file
|
||||
# and mark it to be sent or received from the link.
|
||||
# For alias/multi-topic messages (i.e. the ones found on the '#TOPICS' of the
|
||||
# uORB messages), these can be also added, requiring an extra entry ('base') to
|
||||
# define the base message.
|
||||
#
|
||||
# IMPORTANT NOTICE: The IDs of the messages sent on the bridge get generated
|
||||
# according to the order of the messages in this file. To keep consistency and
|
||||
# backwards compatibility, it is recommended that any new message that one wants
|
||||
# to be streamed in the bridge gets added to the end of the list. Any changes
|
||||
# in the middle of the list (additions, removals, replacements) will change also
|
||||
# the current message IDS, which might result with incompatibilities with
|
||||
# previous PX4 versions (where the list with this format got introduced or
|
||||
# subsisted).
|
||||
#
|
||||
# Any updates to this file should be mirrored in both sides of the bridge (i.e.,
|
||||
# PX4 and px4_ros_com), when using it with ROS2. That can be easily done using
|
||||
# the 'msg/tools/uorb_to_ros_urtps_topics.py' script to regenerate this same
|
||||
# file under 'px4_ros_com/templates/''. The same is not applicable/required if
|
||||
# using this bridge with "raw" RTPS/DDS applications, since the microRTPS agent
|
||||
# to be used and stored in 'build/<px4_target>/src/modules/micrortps_bridge/''
|
||||
# gets generated using this same list.
|
||||
#
|
||||
#####
|
||||
rtps:
|
||||
# topic ID 1
|
||||
- msg: debug_array
|
||||
receive: true
|
||||
# topic ID 2
|
||||
- msg: debug_key_value
|
||||
receive: true
|
||||
# topic ID 3
|
||||
- msg: debug_value
|
||||
receive: true
|
||||
# ...
|
||||
- msg: debug_vect
|
||||
receive: true
|
||||
- msg: offboard_control_mode
|
||||
receive: true
|
||||
- msg: optical_flow
|
||||
receive: true
|
||||
- msg: position_setpoint
|
||||
receive: true
|
||||
- msg: position_setpoint_triplet
|
||||
receive: true
|
||||
- msg: telemetry_status
|
||||
receive: true
|
||||
- msg: timesync
|
||||
receive: true
|
||||
send: true
|
||||
- msg: trajectory_waypoint
|
||||
send: true
|
||||
- msg: vehicle_command
|
||||
receive: true
|
||||
- msg: vehicle_control_mode
|
||||
send: true
|
||||
- msg: vehicle_local_position_setpoint
|
||||
receive: true
|
||||
- msg: trajectory_setpoint # multi-topic / alias of vehicle_local_position_setpoint
|
||||
base: vehicle_local_position_setpoint
|
||||
receive: true
|
||||
- msg: vehicle_odometry
|
||||
send: true
|
||||
- msg: vehicle_mocap_odometry # multi-topic / alias of vehicle_odometry
|
||||
base: vehicle_odometry
|
||||
receive: true
|
||||
- msg: vehicle_visual_odometry # multi-topic / alias of vehicle_odometry
|
||||
base: vehicle_odometry
|
||||
receive: true
|
||||
- msg: vehicle_status
|
||||
send: true
|
||||
- msg: vehicle_trajectory_waypoint
|
||||
receive: true
|
||||
- msg: vehicle_trajectory_waypoint_desired # multi-topic / alias of vehicle_trajectory_waypoint
|
||||
base: vehicle_trajectory_waypoint
|
||||
send: true
|
||||
- msg: collision_constraints
|
||||
send: true
|
||||
- msg: onboard_computer_status
|
||||
receive: true
|
||||
- msg: trajectory_bezier
|
||||
receive: true
|
||||
- msg: vehicle_trajectory_bezier
|
||||
receive: true
|
||||
- msg: timesync_status
|
||||
send: true
|
|
@ -48,7 +48,7 @@ else()
|
|||
message(STATUS "${FASTRTPSGEN_VERSION}")
|
||||
endif()
|
||||
|
||||
if (EXISTS "${PX4_SOURCE_DIR}/msg/tools/uorb_rtps_message_ids.yaml")
|
||||
if (EXISTS "${PX4_SOURCE_DIR}/msg/tools/urtps_bridge_topics.yaml")
|
||||
set(config_rtps_send_topics)
|
||||
execute_process(
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/msg/tools/uorb_rtps_classifier.py -sa
|
||||
|
@ -106,7 +106,8 @@ if (GENERATE_RTPS_BRIDGE)
|
|||
|
||||
# send topic files
|
||||
STRING(REGEX REPLACE ";" ", " send_list "${config_rtps_send_topics};${config_rtps_send_alias_topics}")
|
||||
message(STATUS "RTPS send: ${send_list}")
|
||||
message(STATUS "microRTPS bridge:")
|
||||
message(STATUS " Publish to the bridge from: ${send_list}")
|
||||
set(send_topic_files)
|
||||
foreach(topic ${config_rtps_send_topics})
|
||||
list(APPEND send_topic_files ${PX4_SOURCE_DIR}/msg/${topic}.msg)
|
||||
|
@ -116,7 +117,7 @@ if (GENERATE_RTPS_BRIDGE)
|
|||
|
||||
# receive topic files
|
||||
STRING(REGEX REPLACE ";" ", " rcv_list "${config_rtps_receive_topics};${config_rtps_receive_alias_topics}")
|
||||
message(STATUS "RTPS receive: ${rcv_list}")
|
||||
message(STATUS " Subscribe from the bridge to: ${rcv_list}")
|
||||
set(receive_topic_files)
|
||||
foreach(topic ${config_rtps_receive_topics})
|
||||
list(APPEND receive_topic_files ${PX4_SOURCE_DIR}/msg/${topic}.msg)
|
||||
|
|
Loading…
Reference in New Issue