mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
parse output from python script into readable cmake list to use; refactor RTPS scripts
This commit is contained in:
parent
a9771f13d1
commit
71d1b77bbe
@ -44,7 +44,7 @@ import argparse
|
||||
import shutil
|
||||
import px_generate_uorb_topic_files
|
||||
import px_generate_uorb_topic_helper
|
||||
import uorb_rtps_classifier
|
||||
from uorb_rtps_classifier import Classifier
|
||||
import subprocess
|
||||
import glob
|
||||
import errno
|
||||
@ -69,7 +69,7 @@ def check_rtps_id_uniqueness(classifier):
|
||||
used_ids.sort()
|
||||
|
||||
repeated_keys = dict()
|
||||
for key, value in msg_ids.items():
|
||||
for key, value in msgs_to_use.items():
|
||||
if used_ids.count(value) > 1:
|
||||
repeated_keys.update({key: value})
|
||||
|
||||
@ -196,20 +196,21 @@ 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
|
||||
classifier = Classifier(px_generate_uorb_topic_helper.parse_yaml_msg_id_file(os.path.join(msg_folder, args.yaml_file), msg_folder)
|
||||
classifier = Classifier(px_generate_uorb_topic_helper.parse_yaml_msg_id_file(
|
||||
os.path.join(msg_folder, args.yaml_file)), msg_folder)
|
||||
# check if there are no ID's repeated
|
||||
check_rtps_id_uniqueness(classifier)
|
||||
|
||||
|
||||
uRTPS_CLIENT_TEMPL_FILE='microRTPS_client.cpp.template'
|
||||
uRTPS_AGENT_TOPICS_H_TEMPL_FILE='RtpsTopics.h.template'
|
||||
uRTPS_AGENT_TOPICS_SRC_TEMPL_FILE='RtpsTopics.cpp.template'
|
||||
uRTPS_AGENT_TEMPL_FILE='microRTPS_agent.cpp.template'
|
||||
uRTPS_AGENT_CMAKELISTS_TEMPL_FILE='microRTPS_agent_CMakeLists.txt.template'
|
||||
uRTPS_PUBLISHER_SRC_TEMPL_FILE='Publisher.cpp.template'
|
||||
uRTPS_PUBLISHER_H_TEMPL_FILE='Publisher.h.template'
|
||||
uRTPS_SUBSCRIBER_SRC_TEMPL_FILE='Subscriber.cpp.template'
|
||||
uRTPS_SUBSCRIBER_H_TEMPL_FILE='Subscriber.h.template'
|
||||
uRTPS_CLIENT_TEMPL_FILE = 'microRTPS_client.cpp.template'
|
||||
uRTPS_AGENT_TOPICS_H_TEMPL_FILE = 'RtpsTopics.h.template'
|
||||
uRTPS_AGENT_TOPICS_SRC_TEMPL_FILE = 'RtpsTopics.cpp.template'
|
||||
uRTPS_AGENT_TEMPL_FILE = 'microRTPS_agent.cpp.template'
|
||||
uRTPS_AGENT_CMAKELISTS_TEMPL_FILE = 'microRTPS_agent_CMakeLists.txt.template'
|
||||
uRTPS_PUBLISHER_SRC_TEMPL_FILE = 'Publisher.cpp.template'
|
||||
uRTPS_PUBLISHER_H_TEMPL_FILE = 'Publisher.h.template'
|
||||
uRTPS_SUBSCRIBER_SRC_TEMPL_FILE = 'Subscriber.cpp.template'
|
||||
uRTPS_SUBSCRIBER_H_TEMPL_FILE = 'Subscriber.h.template'
|
||||
|
||||
|
||||
def generate_agent(out_dir):
|
||||
@ -254,12 +255,12 @@ def generate_agent(out_dir):
|
||||
|
||||
# Final steps to install agent
|
||||
mkdir_p(os.path.join(out_dir, "fastrtpsgen"))
|
||||
prev_cwd_path=os.getcwd()
|
||||
prev_cwd_path = os.getcwd()
|
||||
os.chdir(os.path.join(out_dir, "fastrtpsgen"))
|
||||
if not glob.glob(os.path.join(idl_dir, "*.idl")):
|
||||
raise Exception("No IDL files found in %s" % idl_dir)
|
||||
for idl_file in glob.glob(os.path.join(idl_dir, "*.idl")):
|
||||
ret=subprocess.call(fastrtpsgen_path + " -d " + out_dir +
|
||||
ret = subprocess.call(fastrtpsgen_path + " -d " + out_dir +
|
||||
"/fastrtpsgen -example x64Linux2.6gcc " + fastrtpsgen_include + idl_file, shell=True)
|
||||
if ret:
|
||||
raise Exception(
|
||||
@ -308,13 +309,13 @@ def generate_client(out_dir):
|
||||
|
||||
# Rename work in the default path
|
||||
if default_client_out != out_dir:
|
||||
def_file=os.path.join(default_client_out, "microRTPS_client.cpp")
|
||||
def_file = os.path.join(default_client_out, "microRTPS_client.cpp")
|
||||
if os.path.isfile(def_file):
|
||||
os.rename(def_file, def_file.replace(".cpp", ".cpp_"))
|
||||
def_file=os.path.join(default_client_out, "microRTPS_transport.cpp")
|
||||
def_file = os.path.join(default_client_out, "microRTPS_transport.cpp")
|
||||
if os.path.isfile(def_file):
|
||||
os.rename(def_file, def_file.replace(".cpp", ".cpp_"))
|
||||
def_file=os.path.join(default_client_out, "microRTPS_transport.h")
|
||||
def_file = os.path.join(default_client_out, "microRTPS_transport.h")
|
||||
if os.path.isfile(def_file):
|
||||
os.rename(def_file, def_file.replace(".h", ".h_"))
|
||||
|
||||
|
||||
@ -141,7 +141,7 @@ if __name__ == "__main__":
|
||||
# Parse arguments
|
||||
args = parser.parse_args()
|
||||
|
||||
msg_folder = os.path.dirname(os.path.dirname(os.path.abspath(args.msgdir)))
|
||||
msg_folder = os.path.dirname(os.path.dirname(os.path.abspath(__file__)))
|
||||
classifier = Classifier(px_generate_uorb_topic_helper.parse_yaml_msg_id_file(
|
||||
os.path.join(msg_folder, args.yaml_file)), msg_folder)
|
||||
|
||||
@ -150,19 +150,19 @@ if __name__ == "__main__":
|
||||
print ('send files: ' + ', '.join(str(msg_file)
|
||||
for msg_file in classifier.msgs_files_send) + '\n')
|
||||
else:
|
||||
print ('send topics: ' + ', '.join(str(msg)
|
||||
for msg in classifier.msgs_to_send.keys()) + '\n')
|
||||
print (', '.join(str(msg)
|
||||
for msg in classifier.msgs_to_send.keys()) + '\n')
|
||||
if args.receive:
|
||||
if args.path:
|
||||
print ('receive files: ' + ', '.join(str(msg_file)
|
||||
for msg_file in classifier.msgs_files_receive) + '\n')
|
||||
else:
|
||||
print ('receive topics: ' + ', '.join(str(msg)
|
||||
for msg in classifier.msgs_to_receive.keys()) + '\n')
|
||||
print (', '.join(str(msg)
|
||||
for msg in classifier.msgs_to_receive.keys()) + '\n')
|
||||
if args.ignore:
|
||||
if args.path:
|
||||
print ('ignore files: ' + ', '.join(str(msg_file)
|
||||
for msg_file in classifier.msgs_files_ignore) + '\n')
|
||||
else:
|
||||
print ('ignore topics: ' + ', '.join(str(msg)
|
||||
for msg in classifier.msgs_to_ignore.keys()) + '\n')
|
||||
print (', '.join(str(msg)
|
||||
for msg in classifier.msgs_to_ignore.keys()) + '\n')
|
||||
|
||||
@ -69,11 +69,13 @@ rtps:
|
||||
id: 14
|
||||
- msg: obstacle_distance
|
||||
id: 42
|
||||
# multi topics
|
||||
- msg: vehicle_mocap_odometry
|
||||
id: 132
|
||||
- msg: vehicle_visual_odometry
|
||||
id: 133
|
||||
- msg: optical_flow
|
||||
id: 44
|
||||
# multi topics TODO
|
||||
# - msg: vehicle_mocap_odometry
|
||||
# id: 132
|
||||
# - msg: vehicle_visual_odometry
|
||||
# id: 133
|
||||
unclassified:
|
||||
- msg: actuator_armed
|
||||
id: 0
|
||||
@ -141,8 +143,6 @@ rtps:
|
||||
id: 41
|
||||
- msg: offboard_control_mode
|
||||
id: 43
|
||||
- msg: optical_flow
|
||||
id: 44
|
||||
- msg: parameter_update
|
||||
id: 45
|
||||
- msg: ping
|
||||
|
||||
@ -40,20 +40,27 @@ if(NOT FASTRTPSGEN)
|
||||
message(FATAL_ERROR "Unable to find fastrtpsgen")
|
||||
endif()
|
||||
|
||||
set(config_rtps_send_topics
|
||||
sensor_combined
|
||||
sensor_baro
|
||||
sensor_selection
|
||||
vehicle_gps_position
|
||||
airspeed
|
||||
vehicle_land_detected
|
||||
vehicle_status
|
||||
)
|
||||
if (EXISTS "${PX4_SOURCE_DIR}/msg/tools/uorb_rtps_message_ids.yaml")
|
||||
|
||||
set(config_rtps_receive_topics
|
||||
sensor_baro
|
||||
optical_flow
|
||||
)
|
||||
set(config_rtps_send_topics)
|
||||
execute_process(
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/msg/tools/uorb_rtps_classifier.py -s
|
||||
OUTPUT_VARIABLE config_rtps_send_topics
|
||||
)
|
||||
|
||||
STRING(REGEX REPLACE ", " ";" config_rtps_send_topics "${config_rtps_send_topics}")
|
||||
STRING(REGEX REPLACE "\n" "" config_rtps_send_topics "${config_rtps_send_topics}")
|
||||
|
||||
set(config_rtps_receive_topics)
|
||||
execute_process(
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/msg/tools/uorb_rtps_classifier.py -r
|
||||
OUTPUT_VARIABLE config_rtps_receive_topics
|
||||
)
|
||||
|
||||
STRING(REGEX REPLACE ", " ";" config_rtps_receive_topics "${config_rtps_receive_topics}")
|
||||
STRING(REGEX REPLACE "\n" "" config_rtps_receive_topics "${config_rtps_receive_topics}")
|
||||
|
||||
endif()
|
||||
|
||||
if (FASTRTPSGEN AND (config_rtps_send_topics OR config_rtps_receive_topics))
|
||||
option(GENERATE_RTPS_BRIDGE "enable RTPS and microCDR" ON)
|
||||
@ -89,6 +96,7 @@ if (GENERATE_RTPS_BRIDGE)
|
||||
endforeach()
|
||||
|
||||
# receive topic files
|
||||
message(STATUS "RTPS receive: ${config_rtps_receive_topics}")
|
||||
set(receive_topic_files)
|
||||
foreach(topic ${config_rtps_receive_topics})
|
||||
list(APPEND receive_topic_files ${PX4_SOURCE_DIR}/msg/${topic}.msg)
|
||||
|
||||
@ -71,15 +71,9 @@ if (NOT "${config_rtps_send_topics}" STREQUAL "" OR NOT "${config_rtps_receive_t
|
||||
${msg_out_path}/micrortps_client/microRTPS_transport.h
|
||||
)
|
||||
|
||||
# Copy yaml file to the bin dir to be used by empy on the file generation
|
||||
configure_file("${PX4_SOURCE_DIR}/msg/tools/uorb_rtps_message_ids.yaml"
|
||||
"${CMAKE_CURRENT_BINARY_DIR}/uorb_rtps_message_ids.yaml" COPYONLY)
|
||||
|
||||
add_custom_command(OUTPUT ${topic_bridge_files_out}
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/msg/tools/generate_microRTPS_bridge.py
|
||||
--fastrtpsgen-dir $ENV{FASTRTPSGEN_DIR}
|
||||
${send_topic_opt} ${send_topic_files}
|
||||
${receive_topic_opt} ${receive_topic_files}
|
||||
--generate-idl
|
||||
--mkdir-build
|
||||
--generate-cmakelists
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user