mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
msg: RTPS: pass RTPS ID msg definition file as an EmPy global var
This commit is contained in:
@@ -20,14 +20,6 @@ from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
topic_names = [single_spec.short_name for single_spec in spec]
|
||||
send_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND]
|
||||
recv_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.RECEIVE]
|
||||
yaml_file = os.path.abspath('uorb_rtps_message_ids.yaml')
|
||||
try:
|
||||
msg_ids = parse_yaml_msg_id_file(yaml_file)
|
||||
except OSError as e:
|
||||
if e.errno == errno.ENOENT:
|
||||
raise IOError(errno.ENOENT, os.strerror(errno.ENOENT), yaml_file)
|
||||
else:
|
||||
raise
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
@@ -120,7 +112,7 @@ void* send(void* /*unused*/)
|
||||
/* payload is shifted by header length to make room for header*/
|
||||
serialize_@(topic)(&MicroBufferWriter, &data, &data_buffer[header_length], &length);
|
||||
|
||||
if (0 < (read = transport_node->write((char)@(rtps_message_id(msg_ids, topic)), data_buffer, length)))
|
||||
if (0 < (read = transport_node->write((char)@(rtps_message_id(ids, topic)), data_buffer, length)))
|
||||
{
|
||||
total_sent += read;
|
||||
++sent;
|
||||
@@ -196,7 +188,7 @@ void micrortps_start_topics(struct timespec &begin, int &total_read, uint32_t &r
|
||||
{
|
||||
@[for topic in recv_topics]@
|
||||
|
||||
case @(rtps_message_id(msg_ids, topic)):
|
||||
case @(rtps_message_id(ids, topic)):
|
||||
{
|
||||
deserialize_@(topic)(&MicroBufferReader, &@(topic)_data, data_buffer);
|
||||
if (!@(topic)_pub) {
|
||||
|
||||
@@ -19,14 +19,6 @@ from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
topic_names = [single_spec.short_name for single_spec in spec]
|
||||
send_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND]
|
||||
recv_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.RECEIVE]
|
||||
yaml_file = os.path.abspath('uorb_rtps_message_ids.yaml')
|
||||
try:
|
||||
msg_ids = parse_yaml_msg_id_file(yaml_file)
|
||||
except OSError as e:
|
||||
if e.errno == errno.ENOENT:
|
||||
raise IOError(errno.ENOENT, os.strerror(errno.ENOENT), yaml_file)
|
||||
else:
|
||||
raise
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
@@ -97,7 +89,7 @@ void RtpsTopics::publish(uint8_t topic_ID, char data_buffer[], size_t len)
|
||||
switch (topic_ID)
|
||||
{
|
||||
@[for topic in send_topics]@
|
||||
case @(rtps_message_id(msg_ids, topic)): // @(topic)
|
||||
case @(rtps_message_id(ids, topic)): // @(topic)
|
||||
{
|
||||
@(topic)_ st;
|
||||
eprosima::fastcdr::FastBuffer cdrbuffer(data_buffer, len);
|
||||
@@ -125,7 +117,7 @@ bool RtpsTopics::hasMsg(uint8_t *topic_ID)
|
||||
switch (_sub_topics[_next_sub_idx])
|
||||
{
|
||||
@[for topic in recv_topics]@
|
||||
case @(rtps_message_id(msg_ids, topic)): if (_@(topic)_sub.hasMsg()) *topic_ID = @(rtps_message_id(msg_ids, topic)); break;
|
||||
case @(rtps_message_id(ids, topic)): if (_@(topic)_sub.hasMsg()) *topic_ID = @(rtps_message_id(ids, topic)); break;
|
||||
@[end for]@
|
||||
default:
|
||||
printf("Unexpected topic ID to check hasMsg\n");
|
||||
@@ -149,7 +141,7 @@ bool RtpsTopics::getMsg(const uint8_t topic_ID, eprosima::fastcdr::Cdr &scdr)
|
||||
switch (topic_ID)
|
||||
{
|
||||
@[for topic in recv_topics]@
|
||||
case @(rtps_message_id(msg_ids, topic)): // @(topic)
|
||||
case @(rtps_message_id(ids, topic)): // @(topic)
|
||||
if (_@(topic)_sub.hasMsg())
|
||||
{
|
||||
@(topic)_ msg = _@(topic)_sub.getMsg();
|
||||
|
||||
@@ -19,14 +19,6 @@ from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
topic_names = [single_spec.short_name for single_spec in spec]
|
||||
send_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND]
|
||||
recv_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.RECEIVE]
|
||||
yaml_file = os.path.abspath('uorb_rtps_message_ids.yaml')
|
||||
try:
|
||||
msg_ids = parse_yaml_msg_id_file(yaml_file)
|
||||
except OSError as e:
|
||||
if e.errno == errno.ENOENT:
|
||||
raise IOError(errno.ENOENT, os.strerror(errno.ENOENT), yaml_file)
|
||||
else:
|
||||
raise
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
@@ -97,7 +89,7 @@ private:
|
||||
unsigned _next_sub_idx = 0;
|
||||
char _sub_topics[@(len(recv_topics))] = {
|
||||
@[for topic in recv_topics]@
|
||||
@(rtps_message_id(msg_ids, topic)), // @(topic)
|
||||
@(rtps_message_id(ids, topic)), // @(topic)
|
||||
@[end for]@
|
||||
};
|
||||
@[end if]@
|
||||
|
||||
@@ -43,6 +43,7 @@ import os
|
||||
import argparse
|
||||
import shutil
|
||||
import px_generate_uorb_topic_files
|
||||
import px_generate_uorb_topic_helper
|
||||
import subprocess
|
||||
import glob
|
||||
import errno
|
||||
@@ -68,6 +69,7 @@ default_agent_out = get_absolute_path(
|
||||
"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_package_name = px_generate_uorb_topic_files.PACKAGE
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
@@ -94,6 +96,8 @@ parser.add_argument("-b", "--uorb-templates-dir", dest='uorb_templates', type=st
|
||||
help="uORB templates dir, by default msg_dir/templates/uorb_microcdr", default=default_uorb_templates_dir)
|
||||
parser.add_argument("-q", "--urtps-templates-dir", dest='urtps_templates', type=str,
|
||||
help="uRTPS templates dir, by default msg_dir/templates/urtps", default=default_urtps_templates_dir)
|
||||
parser.add_argument("-y", "--rtps-ids-file", dest='yaml_file', type=str,
|
||||
help="RTPS msg IDs definition file, by default tools/uorb_rtps_message_ids.yaml", default=default_rtps_id_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, nargs=1,
|
||||
@@ -147,7 +151,8 @@ else:
|
||||
get_absolute_path(args.fastrtpsgen), "/fastrtpsgen")
|
||||
fastrtpsgen_include = args.fastrtpsgen_include
|
||||
if fastrtpsgen_include is not None and fastrtpsgen_include != '':
|
||||
fastrtpsgen_include = "-I " + get_absolute_path(args.fastrtpsgen_include) + " "
|
||||
fastrtpsgen_include = "-I " + \
|
||||
get_absolute_path(args.fastrtpsgen_include) + " "
|
||||
|
||||
# If nothing specified it's generated both
|
||||
if agent == False and client == False:
|
||||
@@ -180,6 +185,10 @@ if agent and os.path.isdir(os.path.join(agent_out_dir, "idl")):
|
||||
|
||||
uorb_templates_dir = os.path.join(msg_folder, args.uorb_templates)
|
||||
urtps_templates_dir = os.path.join(msg_folder, args.urtps_templates)
|
||||
# parse yaml file into a map of ids
|
||||
rtps_ids = px_generate_uorb_topic_helper.parse_yaml_msg_id_file(
|
||||
os.path.join(msg_folder, args.yaml_file))
|
||||
|
||||
|
||||
uRTPS_CLIENT_TEMPL_FILE = 'microRTPS_client.cpp.template'
|
||||
uRTPS_AGENT_TOPICS_H_TEMPL_FILE = 'RtpsTopics.h.template'
|
||||
@@ -199,38 +208,38 @@ def generate_agent(out_dir):
|
||||
if gen_idl:
|
||||
if out_dir != agent_out_dir:
|
||||
px_generate_uorb_topic_files.generate_idl_file(msg_file, os.path.join(out_dir, "/idl"), urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids)
|
||||
else:
|
||||
px_generate_uorb_topic_files.generate_idl_file(msg_file, idl_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids)
|
||||
px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_PUBLISHER_SRC_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_PUBLISHER_SRC_TEMPL_FILE)
|
||||
px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_PUBLISHER_H_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_PUBLISHER_H_TEMPL_FILE)
|
||||
|
||||
if msg_files_receive:
|
||||
for msg_file in msg_files_receive:
|
||||
if gen_idl:
|
||||
if out_dir != agent_out_dir:
|
||||
px_generate_uorb_topic_files.generate_idl_file(msg_file, os.path.join(out_dir, "/idl"), urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids)
|
||||
else:
|
||||
px_generate_uorb_topic_files.generate_idl_file(msg_file, idl_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids)
|
||||
px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_SUBSCRIBER_SRC_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_SUBSCRIBER_SRC_TEMPL_FILE)
|
||||
px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_SUBSCRIBER_H_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_SUBSCRIBER_H_TEMPL_FILE)
|
||||
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_AGENT_TEMPL_FILE)
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_TOPICS_H_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_AGENT_TOPICS_H_TEMPL_FILE)
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_TOPICS_SRC_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_AGENT_TOPICS_SRC_TEMPL_FILE)
|
||||
if cmakelists:
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_CMAKELISTS_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_AGENT_CMAKELISTS_TEMPL_FILE)
|
||||
|
||||
# Final steps to install agent
|
||||
mkdir_p(os.path.join(out_dir, "fastrtpsgen"))
|
||||
@@ -299,7 +308,7 @@ def generate_client(out_dir):
|
||||
os.rename(def_file, def_file.replace(".h", ".h_"))
|
||||
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, uorb_templates_dir,
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_CLIENT_TEMPL_FILE)
|
||||
package, px_generate_uorb_topic_files.INCL_DEFAULT, rtps_ids, uRTPS_CLIENT_TEMPL_FILE)
|
||||
|
||||
# Final steps to install client
|
||||
cp_wildcard(os.path.join(urtps_templates_dir,
|
||||
|
||||
@@ -170,12 +170,12 @@ def generate_output_from_file(format_idx, filename, outputdir, package, template
|
||||
return generate_by_template(output_file, template_file, em_globals)
|
||||
|
||||
|
||||
def generate_idl_file(filename_msg, outputdir, templatedir, package, includepath):
|
||||
def generate_idl_file(filename_msg, outputdir, templatedir, package, includepath, ids):
|
||||
"""
|
||||
Generates an .idl from .msg file
|
||||
"""
|
||||
em_globals = get_em_globals(
|
||||
filename_msg, package, includepath, MsgScope.NONE)
|
||||
filename_msg, package, includepath, ids, MsgScope.NONE)
|
||||
spec_short_name = em_globals["spec"].short_name
|
||||
|
||||
# Make sure output directory exists:
|
||||
@@ -190,18 +190,18 @@ def generate_idl_file(filename_msg, outputdir, templatedir, package, includepath
|
||||
|
||||
|
||||
def generate_uRTPS_general(filename_send_msgs, filename_received_msgs,
|
||||
outputdir, templatedir, package, includepath, template_name):
|
||||
outputdir, templatedir, package, includepath, ids, template_name):
|
||||
"""
|
||||
Generates source file by msg content
|
||||
"""
|
||||
em_globals_list = []
|
||||
if filename_send_msgs:
|
||||
em_globals_list.extend([get_em_globals(
|
||||
f, package, includepath, MsgScope.SEND) for f in filename_send_msgs])
|
||||
f, package, includepath, ids, MsgScope.SEND) for f in filename_send_msgs])
|
||||
|
||||
if filename_received_msgs:
|
||||
em_globals_list.extend([get_em_globals(
|
||||
f, package, includepath, MsgScope.RECEIVE) for f in filename_received_msgs])
|
||||
f, package, includepath, ids, MsgScope.RECEIVE) for f in filename_received_msgs])
|
||||
|
||||
merged_em_globals = merge_em_globals_list(em_globals_list)
|
||||
# Make sure output directory exists:
|
||||
@@ -215,12 +215,12 @@ def generate_uRTPS_general(filename_send_msgs, filename_received_msgs,
|
||||
return generate_by_template(output_file, template_file, merged_em_globals)
|
||||
|
||||
|
||||
def generate_topic_file(filename_msg, outputdir, templatedir, package, includepath, template_name):
|
||||
def generate_topic_file(filename_msg, outputdir, templatedir, package, includepath, ids, template_name):
|
||||
"""
|
||||
Generates an .idl from .msg file
|
||||
"""
|
||||
em_globals = get_em_globals(
|
||||
filename_msg, package, includepath, MsgScope.NONE)
|
||||
filename_msg, package, includepath, ids, MsgScope.NONE)
|
||||
spec_short_name = em_globals["spec"].short_name
|
||||
|
||||
# Make sure output directory exists:
|
||||
@@ -234,7 +234,7 @@ def generate_topic_file(filename_msg, outputdir, templatedir, package, includepa
|
||||
return generate_by_template(output_file, template_file, em_globals)
|
||||
|
||||
|
||||
def get_em_globals(filename_msg, package, includepath, scope):
|
||||
def get_em_globals(filename_msg, package, includepath, ids, scope):
|
||||
"""
|
||||
Generates em globals dictionary
|
||||
"""
|
||||
@@ -259,6 +259,7 @@ def get_em_globals(filename_msg, package, includepath, scope):
|
||||
"msg_context": msg_context,
|
||||
"spec": spec,
|
||||
"topics": topics,
|
||||
"ids": ids,
|
||||
"scope": scope
|
||||
}
|
||||
|
||||
|
||||
@@ -370,7 +370,7 @@ def rtps_message_id(msg_id_map, message):
|
||||
"""
|
||||
Get RTPS ID of uORB message
|
||||
"""
|
||||
for dict in msg_id_map["rtps"]:
|
||||
if message in dict["msg"]:
|
||||
return dict["id"]
|
||||
for dict in msg_id_map[0]['rtps']:
|
||||
if message in dict['msg']:
|
||||
return dict['id']
|
||||
return 0
|
||||
|
||||
@@ -84,8 +84,9 @@ if (NOT "${config_rtps_send_topics}" STREQUAL "" OR NOT "${config_rtps_receive_t
|
||||
--mkdir-build
|
||||
--generate-cmakelists
|
||||
--topic-msg-dir ${PX4_SOURCE_DIR}/msg
|
||||
--uorb-templates-dir "templates/uorb_microcdr"
|
||||
--urtps-templates-dir "templates/urtps"
|
||||
--uorb-templates-dir templates/uorb_microcdr
|
||||
--urtps-templates-dir templates/urtps
|
||||
--rtps-ids-file tools/uorb_rtps_message_ids.yaml
|
||||
--agent-outdir ${CMAKE_CURRENT_BINARY_DIR}/micrortps_agent
|
||||
--client-outdir ${CMAKE_CURRENT_BINARY_DIR}/micrortps_client
|
||||
--idl-dir ${CMAKE_CURRENT_BINARY_DIR}/micrortps_agent/idl
|
||||
|
||||
Reference in New Issue
Block a user