mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-22 14:24:21 +08:00
Fixing rebase conflicts
This commit is contained in:
committed by
Lorenz Meier
parent
d69c53827f
commit
c85039e413
@@ -62,6 +62,7 @@ GTAGS
|
||||
*.creator.user
|
||||
*.files
|
||||
*.includes
|
||||
src/modules/micrortps_bridge/micrortps_agent/
|
||||
|
||||
# uavcan firmware
|
||||
ROMFS/px4fmu_common/uavcan/
|
||||
|
||||
@@ -37,3 +37,6 @@
|
||||
[submodule "src/drivers/gps/devices"]
|
||||
path = src/drivers/gps/devices
|
||||
url = https://github.com/PX4/GpsDrivers.git
|
||||
[submodule "src/lib/micro-CDR"]
|
||||
path = src/lib/micro-CDR
|
||||
url = https://github.com/eProsima/micro-CDR.git
|
||||
|
||||
+4
-1
@@ -204,6 +204,7 @@ px4_add_git_submodule(TARGET git_mavlink PATH "mavlink/include/mavlink/v1.0")
|
||||
px4_add_git_submodule(TARGET git_mavlink2 PATH "mavlink/include/mavlink/v2.0")
|
||||
px4_add_git_submodule(TARGET git_nuttx PATH "NuttX")
|
||||
px4_add_git_submodule(TARGET git_uavcan PATH "src/modules/uavcan/libuavcan")
|
||||
px4_add_git_submodule(TARGET git_micro_cdr PATH "src/lib/micro-CDR")
|
||||
|
||||
px4_create_git_hash_header()
|
||||
|
||||
@@ -380,8 +381,10 @@ px4_generate_messages(TARGET msg_gen
|
||||
MSG_FILES ${msg_files}
|
||||
OS ${OS}
|
||||
INCLUDES ${msg_include_paths}
|
||||
DEPENDS git_genmsg git_gencpp prebuild_targets
|
||||
DEPENDS git_genmsg git_gencpp git_micro_cdr prebuild_targets
|
||||
)
|
||||
include_directories("${PX4_SOURCE_DIR}/src/lib/micro-CDR/include"
|
||||
"${PX4_BINARY_DIR}/src/lib/micro-CDR/include/microcdr")
|
||||
|
||||
px4_generate_airframes_xml(BOARD ${BOARD})
|
||||
|
||||
|
||||
@@ -62,7 +62,7 @@ The PX4 Dev Team syncs up on a [weekly dev call](https://dev.px4.io/en/contribut
|
||||
* Obstacle Avoidance - [Vilhjalmur Vilhjalmsson](https://github.com/vilhjalmur89)
|
||||
* [Snapdragon](https://github.com/PX4/Firmware/labels/snapdragon)
|
||||
* [Christoph Tobler](https://github.com/ChristophTobler)
|
||||
* [Mark Charlebois](https://github.com/mcharleb)
|
||||
* [Mark Charlebois](https://github.com/mcharleb)
|
||||
* [Intel Aero](https://github.com/PX4/Firmware/labels/intel%20aero)
|
||||
* [Lucas De Marchi](https://github.com/lucasdemarchi)
|
||||
* [José Roberto de Souza](https://github.com/zehortigoza)
|
||||
|
||||
@@ -0,0 +1,191 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
################################################################################
|
||||
#
|
||||
# Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||||
#
|
||||
# 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 of the copyright holder 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 HOLDER 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.
|
||||
#
|
||||
################################################################################
|
||||
|
||||
import sys, os, argparse, shutil
|
||||
import px_generate_uorb_topic_files
|
||||
import subprocess, glob
|
||||
|
||||
def get_absolute_path(arg_parse_dir):
|
||||
root_path = os.path.dirname(os.path.dirname(os.path.abspath(__file__)))
|
||||
|
||||
if isinstance(arg_parse_dir, list):
|
||||
dir = arg_parse_dir[0]
|
||||
else:
|
||||
dir = arg_parse_dir
|
||||
|
||||
if dir[0] != '/':
|
||||
dir = root_path + "/" + dir
|
||||
|
||||
return dir
|
||||
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument("-s", "--send", dest='send', metavar='*.msg', type=str, nargs='+', help="Topics to be sended")
|
||||
parser.add_argument("-r", "--receive", dest='receive', metavar='*.msg', type=str, nargs='+', help="Topics to be received")
|
||||
parser.add_argument("-a", "--agent", dest='agent', action="store_true", help="Flag for generate the agent, by default is true if -c is not specified")
|
||||
parser.add_argument("-c", "--client", dest='client', action="store_true", help="Flag for generate the client, by default is true if -a is not specified")
|
||||
parser.add_argument("-t", "--topic-msg-dir", dest='msgdir', type=str, nargs=1, help="Topics message dir, by default msg/", default="msg")
|
||||
parser.add_argument("-o", "--agent-outdir", dest='agentdir', type=str, nargs=1, help="Agent output dir, by default src/modules/micrortps_bridge/micrortps_agent", default="src/modules/micrortps_bridge/micrortps_agent")
|
||||
parser.add_argument("-u", "--client-outdir", dest='clientdir', type=str, nargs=1, help="Client output dir, by default src/modules/micrortps_bridge/micrortps_client", default="src/modules/micrortps_bridge/micrortps_client")
|
||||
parser.add_argument("-f", "--fastrtpsgen-dir", dest='fastrtpsgen', type=str, nargs='?', help="fastrtpsgen installation dir, only needed if fastrtpsgen is not in PATH, by default empty", default="")
|
||||
parser.add_argument("--delete-tree", dest='del_tree', action="store_true", help="Delete dir tree output dir(s)")
|
||||
|
||||
if len(sys.argv) <= 1:
|
||||
parser.print_usage()
|
||||
exit(-1)
|
||||
|
||||
# Parse arguments
|
||||
args = parser.parse_args()
|
||||
msg_folder = get_absolute_path(args.msgdir)
|
||||
msg_files_send = args.send
|
||||
msg_files_receive = args.receive
|
||||
agent = args.agent
|
||||
client = args.client
|
||||
del_tree = args.del_tree
|
||||
px_generate_uorb_topic_files.append_to_include_path({msg_folder}, px_generate_uorb_topic_files.INCL_DEFAULT)
|
||||
agent_out_dir = get_absolute_path(args.agentdir)
|
||||
client_out_dir = get_absolute_path(args.clientdir)
|
||||
|
||||
if args.fastrtpsgen is None or args.fastrtpsgen == "":
|
||||
# Assume fastrtpsgen is in PATH
|
||||
fastrtpsgen_path = "fastrtpsgen"
|
||||
else:
|
||||
# Path to fastrtpsgen is explicitly specified
|
||||
fastrtpsgen_path = get_absolute_path(args.fastrtpsgen) + "/fastrtpsgen"
|
||||
|
||||
# If nothing specified it's generated both
|
||||
if agent == False and client == False:
|
||||
agent = True
|
||||
client = True
|
||||
|
||||
if del_tree:
|
||||
if agent:
|
||||
_continue = str(raw_input("\nFiles in " + agent_out_dir + " will be erased, continue?[Y/n]\n"))
|
||||
if _continue == "N" or _continue == "n":
|
||||
print("Aborting execution...")
|
||||
exit(-1)
|
||||
else:
|
||||
if agent and os.path.isdir(agent_out_dir):
|
||||
shutil.rmtree(agent_out_dir)
|
||||
|
||||
if client:
|
||||
_continue = str(raw_input("\nFiles in " + client_out_dir + " will be erased, continue?[Y/n]\n"))
|
||||
if _continue == "N" or _continue == "n":
|
||||
print("Aborting execution...")
|
||||
exit(-1)
|
||||
else:
|
||||
if client and os.path.isdir(client_out_dir):
|
||||
shutil.rmtree(client_out_dir)
|
||||
|
||||
if agent and os.path.isdir(agent_out_dir + "/idl"):
|
||||
shutil.rmtree(agent_out_dir + "/idl")
|
||||
|
||||
uorb_templates_dir = msg_folder + "/templates/uorb"
|
||||
urtps_templates_dir = msg_folder + "/templates/urtps"
|
||||
|
||||
uRTPS_CLIENT_TEMPL_FILE = 'microRTPS_client.cpp.template'
|
||||
uRTPS_AGENT_TOPICS_H_TEMPL_FILE = 'RtpsTopics.h.template'
|
||||
uRTPS_AGENT_TOPICS_SRC_TEMPL_FILE = 'RtpsTopics.cxx.template'
|
||||
uRTPS_AGENT_TEMPL_FILE = 'microRTPS_agent.cxx.template'
|
||||
uRTPS_AGENT_CMAKELIST_TEMPL_FILE = 'microRTPS_agent_CMakeLists.txt.template'
|
||||
uRTPS_PUBLISHER_SRC_TEMPL_FILE = 'Publisher.cxx.template'
|
||||
uRTPS_PUBLISHER_H_TEMPL_FILE = 'Publisher.h.template'
|
||||
uRTPS_SUBSCRIBER_SRC_TEMPL_FILE = 'Subscriber.cxx.template'
|
||||
uRTPS_SUBSCRIBER_H_TEMPL_FILE = 'Subscriber.h.template'
|
||||
|
||||
def generate_agent(out_dir):
|
||||
|
||||
if msg_files_send:
|
||||
for msg_file in msg_files_send:
|
||||
px_generate_uorb_topic_files.generate_idl_file(msg_file, out_dir + "/idl", urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT)
|
||||
px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_PUBLISHER_SRC_TEMPL_FILE)
|
||||
px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_PUBLISHER_H_TEMPL_FILE)
|
||||
|
||||
if msg_files_receive:
|
||||
for msg_file in msg_files_receive:
|
||||
px_generate_uorb_topic_files.generate_idl_file(msg_file, out_dir + "/idl", urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT)
|
||||
px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_SUBSCRIBER_SRC_TEMPL_FILE)
|
||||
px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_SUBSCRIBER_H_TEMPL_FILE)
|
||||
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_TEMPL_FILE)
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, 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,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_TOPICS_SRC_TEMPL_FILE)
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_CMAKELIST_TEMPL_FILE)
|
||||
|
||||
# Final steps to install agent
|
||||
os.system("mkdir -p " + agent_out_dir + "/fastrtpsgen")
|
||||
for idl_file in glob.glob( agent_out_dir + "/idl/*.idl"):
|
||||
ret = os.system("cd " + agent_out_dir + "/fastrtpsgen && " + fastrtpsgen_path + " -example x64Linux2.6gcc " + idl_file)
|
||||
if ret:
|
||||
raise Exception("fastrtpsgen not found. Specify the location of fastrtpsgen with the -f flag")
|
||||
|
||||
os.system("rm " + agent_out_dir + "/fastrtpsgen/*PubSubMain.cxx "
|
||||
+ agent_out_dir + "/fastrtpsgen/makefile* "
|
||||
+ agent_out_dir + "/fastrtpsgen/*Publisher* "
|
||||
+ agent_out_dir + "/fastrtpsgen/*Subscriber*")
|
||||
os.system("cp " + agent_out_dir + "/fastrtpsgen/* " + agent_out_dir)
|
||||
os.system("rm -rf " + agent_out_dir + "/fastrtpsgen/")
|
||||
os.system("cp " + urtps_templates_dir + "/microRTPS_transport.* " + agent_out_dir)
|
||||
os.system("mv " + agent_out_dir + "/microRTPS_agent_CMakeLists.txt " + agent_out_dir + "/CMakeLists.txt")
|
||||
os.system("mkdir -p " + agent_out_dir + "/build")
|
||||
|
||||
return 0
|
||||
|
||||
def generate_client(out_dir):
|
||||
|
||||
px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, uorb_templates_dir,
|
||||
px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_CLIENT_TEMPL_FILE)
|
||||
|
||||
# Final steps to install client
|
||||
os.system("cp " + urtps_templates_dir + "/microRTPS_transport.* " + client_out_dir)
|
||||
|
||||
return 0
|
||||
|
||||
if agent:
|
||||
generate_agent(agent_out_dir)
|
||||
print("\nAgent created in: " + agent_out_dir)
|
||||
|
||||
if client:
|
||||
generate_client(client_out_dir)
|
||||
print("\nClient created in: " + client_out_dir)
|
||||
@@ -0,0 +1,108 @@
|
||||
|
||||
# Message identification constants
|
||||
|
||||
|
||||
msg_id_map = {
|
||||
'actuator_armed': 1,
|
||||
'actuator_controls': 2,
|
||||
'actuator_direct': 3,
|
||||
'actuator_outputs': 4,
|
||||
'adc_report': 5,
|
||||
'airspeed': 6,
|
||||
'att_pos_mocap': 7,
|
||||
'battery_status': 8,
|
||||
'camera_capture': 9,
|
||||
'camera_trigger': 10,
|
||||
'collision_report': 11,
|
||||
'commander_state': 12,
|
||||
'control_state': 13,
|
||||
'cpuload': 14,
|
||||
'debug_key_value': 15,
|
||||
'differential_pressure': 16,
|
||||
'distance_sensor': 17,
|
||||
'ekf2_innovations': 18,
|
||||
'ekf2_replay': 19,
|
||||
'ekf2_timestamps': 20,
|
||||
'esc_report': 21,
|
||||
'esc_status': 22,
|
||||
'estimator_status': 23,
|
||||
'fence': 24,
|
||||
'fence_vertex': 25,
|
||||
'filtered_bottom_flow': 26,
|
||||
'follow_target': 27,
|
||||
'fw_pos_ctrl_status': 28,
|
||||
'geofence_result': 29,
|
||||
'gps_dump': 30,
|
||||
'gps_inject_data': 31,
|
||||
'hil_sensor': 32,
|
||||
'home_position': 33,
|
||||
'input_rc': 34,
|
||||
'led_control': 35,
|
||||
'log_message': 36,
|
||||
'manual_control_setpoint': 37,
|
||||
'mavlink_log': 38,
|
||||
'mc_att_ctrl_status': 39,
|
||||
'mission': 40,
|
||||
'mission_result': 41,
|
||||
'mount_orientation': 42,
|
||||
'multirotor_motor_limits': 43,
|
||||
'offboard_control_mode': 44,
|
||||
'optical_flow': 45,
|
||||
'output_pwm': 46,
|
||||
'parameter_update': 47,
|
||||
'position_setpoint': 48,
|
||||
'position_setpoint_triplet': 49,
|
||||
'pwm_input': 50,
|
||||
'qshell_req': 51,
|
||||
'rc_channels': 52,
|
||||
'rc_parameter_map': 53,
|
||||
'safety': 54,
|
||||
'satellite_info': 55,
|
||||
'sensor_accel': 56,
|
||||
'sensor_baro': 57,
|
||||
'sensor_combined': 58,
|
||||
'sensor_correction': 59,
|
||||
'sensor_gyro': 60,
|
||||
'sensor_mag': 61,
|
||||
'sensor_preflight': 62,
|
||||
'sensor_selection': 63,
|
||||
'servorail_status': 64,
|
||||
'subsystem_info': 65,
|
||||
'system_power': 66,
|
||||
'task_stack_info': 67,
|
||||
'tecs_status': 68,
|
||||
'telemetry_status': 69,
|
||||
'test_motor': 70,
|
||||
'time_offset': 71,
|
||||
'transponder_report': 72,
|
||||
'uavcan_parameter_request': 73,
|
||||
'uavcan_parameter_value': 74,
|
||||
'ulog_stream_ack': 75,
|
||||
'ulog_stream': 76,
|
||||
'vehicle_attitude': 77,
|
||||
'vehicle_attitude_setpoint': 78,
|
||||
'vehicle_command_ack': 79,
|
||||
'vehicle_command': 80,
|
||||
'vehicle_control_mode': 81,
|
||||
'vehicle_force_setpoint': 82,
|
||||
'vehicle_global_position': 83,
|
||||
'vehicle_global_velocity_setpoint': 84,
|
||||
'vehicle_gps_position': 85,
|
||||
'vehicle_land_detected': 86,
|
||||
'vehicle_local_position': 87,
|
||||
'vehicle_local_position_setpoint': 88,
|
||||
'vehicle_rates_setpoint': 89,
|
||||
'vehicle_roi': 90,
|
||||
'vehicle_status_flags': 91,
|
||||
'vehicle_status': 92,
|
||||
'vtol_vehicle_status': 93,
|
||||
'wind_estimate': 94,
|
||||
}
|
||||
|
||||
def message_id(message):
|
||||
"""
|
||||
Get id of a message
|
||||
"""
|
||||
if message in msg_id_map:
|
||||
return msg_id_map[message]
|
||||
return 0
|
||||
@@ -42,8 +42,8 @@ import os
|
||||
import shutil
|
||||
import filecmp
|
||||
import argparse
|
||||
|
||||
import sys
|
||||
|
||||
px4_tools_dir = os.path.dirname(os.path.abspath(__file__))
|
||||
sys.path.append(px4_tools_dir + "/genmsg/src")
|
||||
sys.path.append(px4_tools_dir + "/gencpp/src")
|
||||
@@ -82,7 +82,12 @@ OUTPUT_FILE_EXT = ['.h', '.cpp']
|
||||
INCL_DEFAULT = ['std_msgs:./msg/std_msgs']
|
||||
PACKAGE = 'px4'
|
||||
TOPICS_TOKEN = '# TOPICS '
|
||||
IDL_TEMPLATE_FILE = 'msg.idl.template'
|
||||
|
||||
class MsgScope:
|
||||
NONE = 0
|
||||
SEND = 1
|
||||
RECEIVE = 2
|
||||
|
||||
def get_multi_topics(filename):
|
||||
"""
|
||||
@@ -141,6 +146,102 @@ def generate_output_from_file(format_idx, filename, outputdir, templatedir, incl
|
||||
|
||||
return generate_by_template(output_file, template_file, em_globals)
|
||||
|
||||
def generate_idl_file(filename_msg, outputdir, templatedir, includepath):
|
||||
"""
|
||||
Generates an .idl from .msg file
|
||||
"""
|
||||
em_globals = get_em_globals(filename_msg, includepath, MsgScope.NONE)
|
||||
spec_short_name = em_globals["spec"].short_name
|
||||
|
||||
# Make sure output directory exists:
|
||||
if not os.path.isdir(outputdir):
|
||||
os.makedirs(outputdir)
|
||||
|
||||
template_file = os.path.join(templatedir, IDL_TEMPLATE_FILE)
|
||||
output_file = os.path.join(outputdir, IDL_TEMPLATE_FILE.replace("msg.idl.template", str(spec_short_name + "_.idl")))
|
||||
|
||||
return generate_by_template(output_file, template_file, em_globals)
|
||||
|
||||
def generate_uRTPS_general(filename_send_msgs, filename_received_msgs,
|
||||
outputdir, templatedir, includepath, template_name):
|
||||
"""
|
||||
Generates source file by UART msg content
|
||||
"""
|
||||
em_globals_list = []
|
||||
if filename_send_msgs:
|
||||
em_globals_list.extend([get_em_globals(f, includepath, MsgScope.SEND) for f in filename_send_msgs])
|
||||
|
||||
if filename_received_msgs:
|
||||
em_globals_list.extend([get_em_globals(f, includepath, MsgScope.RECEIVE) for f in filename_received_msgs])
|
||||
|
||||
merged_em_globals = merge_em_globals_list(em_globals_list)
|
||||
# Make sure output directory exists:
|
||||
if not os.path.isdir(outputdir):
|
||||
os.makedirs(outputdir)
|
||||
|
||||
template_file = os.path.join(templatedir, template_name)
|
||||
output_file = os.path.join(outputdir, template_name.replace(".template", ""))
|
||||
|
||||
return generate_by_template(output_file, template_file, merged_em_globals)
|
||||
|
||||
def generate_topic_file(filename_msg, outputdir, templatedir, includepath, template_name):
|
||||
"""
|
||||
Generates an .idl from .msg file
|
||||
"""
|
||||
em_globals = get_em_globals(filename_msg, includepath, MsgScope.NONE)
|
||||
spec_short_name = em_globals["spec"].short_name
|
||||
|
||||
# Make sure output directory exists:
|
||||
if not os.path.isdir(outputdir):
|
||||
os.makedirs(outputdir)
|
||||
|
||||
template_file = os.path.join(templatedir, template_name)
|
||||
output_file = os.path.join(outputdir, spec_short_name + "_" + template_name.replace(".template", ""))
|
||||
|
||||
return generate_by_template(output_file, template_file, em_globals)
|
||||
|
||||
def get_em_globals(filename_msg, includepath, scope):
|
||||
"""
|
||||
Generates em globals dictionary
|
||||
"""
|
||||
msg_context = genmsg.msg_loader.MsgContext.create_default()
|
||||
full_type_name = genmsg.gentools.compute_full_type_name(PACKAGE, os.path.basename(filename_msg))
|
||||
spec = genmsg.msg_loader.load_msg_from_file(msg_context, filename_msg, full_type_name)
|
||||
topics = get_multi_topics(filename_msg)
|
||||
if includepath:
|
||||
search_path = genmsg.command_line.includepath_to_dict(includepath)
|
||||
else:
|
||||
search_path = {}
|
||||
genmsg.msg_loader.load_depends(msg_context, spec, search_path)
|
||||
md5sum = genmsg.gentools.compute_md5(msg_context, spec)
|
||||
if len(topics) == 0:
|
||||
topics.append(spec.short_name)
|
||||
em_globals = {
|
||||
"file_name_in": filename_msg,
|
||||
"md5sum": md5sum,
|
||||
"search_path": search_path,
|
||||
"msg_context": msg_context,
|
||||
"spec": spec,
|
||||
"topics": topics,
|
||||
"scope": scope
|
||||
}
|
||||
|
||||
return em_globals
|
||||
|
||||
def merge_em_globals_list(em_globals_list):
|
||||
"""
|
||||
Merges a list of em_globals to a single dictionary where each attribute is a list
|
||||
"""
|
||||
if len(em_globals_list) < 1:
|
||||
return {}
|
||||
|
||||
merged_em_globals = {}
|
||||
for name in em_globals_list[0]:
|
||||
merged_em_globals[name] = [em_globals[name] for em_globals in em_globals_list]
|
||||
|
||||
return merged_em_globals
|
||||
|
||||
|
||||
|
||||
def generate_by_template(output_file, template_file, em_globals):
|
||||
"""
|
||||
@@ -151,7 +252,7 @@ def generate_by_template(output_file, template_file, em_globals):
|
||||
folder_name = os.path.dirname(output_file)
|
||||
if not os.path.exists(folder_name):
|
||||
os.makedirs(folder_name)
|
||||
|
||||
|
||||
ofile = open(output_file, 'w')
|
||||
# todo, reuse interpreter
|
||||
interpreter = em.Interpreter(output=ofile, globals=em_globals, options={em.RAW_OPT:True,em.BUFFERED_OPT:True})
|
||||
@@ -268,7 +369,7 @@ def generate_topics_list_file(msgdir, outputdir, templatedir):
|
||||
tl_template_file = os.path.join(templatedir, TOPICS_LIST_TEMPLATE_FILE)
|
||||
tl_out_file = os.path.join(outputdir, TOPICS_LIST_TEMPLATE_FILE.replace(".template", ""))
|
||||
generate_by_template(tl_out_file, tl_template_file, tl_globals)
|
||||
|
||||
|
||||
def generate_topics_list_file_from_files(files, outputdir, templatedir):
|
||||
# generate cpp file with topics list
|
||||
filenames = [os.path.basename(p) for p in files if os.path.basename(p).endswith(".msg")]
|
||||
|
||||
@@ -23,6 +23,36 @@ type_map = {
|
||||
'char': 'char',
|
||||
}
|
||||
|
||||
type_serialize_map = {
|
||||
'int8': 'SignedChar',
|
||||
'int16': 'Short',
|
||||
'int32': 'Int',
|
||||
'int64': 'Long',
|
||||
'uint8': 'UnsignedChar',
|
||||
'uint16': 'UnsignedShort',
|
||||
'uint32': 'UnsignedInt',
|
||||
'uint64': 'UnsignedLong',
|
||||
'float32': 'Float',
|
||||
'float64': 'Double',
|
||||
'bool': 'Bool',
|
||||
'char': 'Char',
|
||||
}
|
||||
|
||||
type_idl_map = {
|
||||
'int8': 'octet',
|
||||
'int16': 'short',
|
||||
'int32': 'long',
|
||||
'int64': 'long long',
|
||||
'uint8': 'octet',
|
||||
'uint16': 'unsigned short',
|
||||
'uint32': 'unsigned long',
|
||||
'uint64': 'unsigned long long',
|
||||
'float32': 'float',
|
||||
'float64': 'double',
|
||||
'bool': 'boolean',
|
||||
'char': 'char',
|
||||
}
|
||||
|
||||
msgtype_size_map = {
|
||||
'int8': 1,
|
||||
'int16': 2,
|
||||
|
||||
@@ -131,6 +131,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -108,6 +108,7 @@ set(config_module_list
|
||||
lib/DriverFramework/framework
|
||||
lib/rc
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -152,6 +152,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -100,6 +100,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -76,6 +76,7 @@ set(config_module_list
|
||||
platforms/nuttx
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
lib/micro-CDR
|
||||
|
||||
|
||||
)
|
||||
|
||||
@@ -156,6 +156,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -48,6 +48,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -67,6 +67,7 @@ set(config_module_list
|
||||
platforms/nuttx
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
lib/micro-CDR
|
||||
|
||||
|
||||
)
|
||||
|
||||
@@ -76,6 +76,7 @@ set(config_module_list
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
modules/uORB
|
||||
lib/micro-CDR
|
||||
|
||||
)
|
||||
|
||||
|
||||
@@ -125,6 +125,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -155,6 +155,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -150,6 +150,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -159,6 +159,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/terrain_estimation
|
||||
lib/version
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# Platform
|
||||
|
||||
@@ -141,6 +141,9 @@ set(config_module_list
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
|
||||
# micro RTPS
|
||||
modules/micrortps_bridge/micrortps_client
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
@@ -161,6 +164,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
@@ -203,6 +207,17 @@ set(config_module_list
|
||||
examples/ekf_att_pos_estimator
|
||||
)
|
||||
|
||||
set(GENERATE_RTPS_BRIDGE on)
|
||||
|
||||
set(config_rtps_send_topics
|
||||
sensor_combined
|
||||
)
|
||||
|
||||
set(config_rtps_receive_topics
|
||||
sensor_baro
|
||||
)
|
||||
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
serdis
|
||||
sercon
|
||||
|
||||
@@ -160,6 +160,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/terrain_estimation
|
||||
lib/version
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# Platform
|
||||
|
||||
@@ -159,6 +159,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/terrain_estimation
|
||||
lib/version
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# Platform
|
||||
|
||||
@@ -139,6 +139,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -106,6 +106,7 @@ set(config_module_list
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
lib/micro-CDR
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
|
||||
@@ -88,6 +88,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# POSIX
|
||||
|
||||
@@ -47,6 +47,7 @@ set(config_module_list
|
||||
lib/conversion
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
|
||||
@@ -19,6 +19,7 @@ set(config_module_list
|
||||
modules/uORB
|
||||
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
|
||||
@@ -93,6 +93,7 @@ set(config_module_list
|
||||
lib/DriverFramework/framework
|
||||
lib/rc
|
||||
lib/led
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# POSIX
|
||||
|
||||
@@ -101,6 +101,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# POSIX
|
||||
|
||||
@@ -65,6 +65,9 @@ set(config_module_list
|
||||
modules/commander
|
||||
modules/navigator
|
||||
|
||||
# micro RTPS
|
||||
modules/micrortps_bridge/micrortps_client
|
||||
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
@@ -78,6 +81,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
|
||||
@@ -57,6 +57,9 @@ set(config_module_list
|
||||
modules/commander
|
||||
modules/navigator
|
||||
|
||||
# micro RTPS
|
||||
modules/micrortps_bridge/micrortps_client
|
||||
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
@@ -70,6 +73,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
|
||||
@@ -104,6 +104,9 @@ set(config_module_list
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
|
||||
# micro RTPS
|
||||
modules/micrortps_bridge/micrortps_client
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
@@ -171,6 +174,9 @@ set(config_module_list
|
||||
|
||||
# EKF
|
||||
examples/ekf_att_pos_estimator
|
||||
|
||||
# micro-RTPS
|
||||
lib/micro-CDR
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
@@ -178,6 +184,16 @@ set(config_extra_builtin_cmds
|
||||
sercon
|
||||
)
|
||||
|
||||
set(GENERATE_RTPS_BRIDGE on)
|
||||
|
||||
set(config_rtps_send_topics
|
||||
sensor_baro
|
||||
)
|
||||
|
||||
set(config_rtps_receive_topics
|
||||
sensor_combined
|
||||
)
|
||||
|
||||
# Default config_sitl_rcS_dir (posix_sitl_default), this is overwritten later
|
||||
# for the config posix_sitl_efk2 and set again, explicitly, for posix_sitl_lpe,
|
||||
# which are based on posix_sitl_default.
|
||||
|
||||
@@ -28,6 +28,7 @@ set(config_module_list
|
||||
lib/geo_lookup
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
|
||||
@@ -34,6 +34,11 @@ set(config_module_list
|
||||
modules/systemlib/param
|
||||
modules/systemlib
|
||||
modules/uORB
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
||||
@@ -73,6 +73,7 @@ set(config_module_list
|
||||
lib/controllib
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
||||
@@ -45,6 +45,7 @@ set(config_module_list
|
||||
lib/conversion
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
||||
@@ -43,6 +43,7 @@ set(config_module_list
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
||||
@@ -79,6 +79,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
||||
@@ -94,6 +94,7 @@ set(config_module_list
|
||||
lib/rc
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
||||
@@ -93,6 +93,7 @@ set(config_module_list
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/micro-CDR
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
||||
@@ -0,0 +1,406 @@
|
||||
@###############################################
|
||||
@#
|
||||
@# EmPy template for generating microRTPS_client.cpp file
|
||||
@#
|
||||
@###############################################
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - msgs (List) list of all msg files
|
||||
@# - multi_topics (List) list of all multi-topic names
|
||||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import gencpp
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
from message_id import * # 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]
|
||||
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||||
*
|
||||
* 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 of the copyright holder 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 HOLDER 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_posix.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <termios.h>
|
||||
#include <ctime>
|
||||
#include <pthread.h>
|
||||
|
||||
#include <microcdr/microCdr.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include "microRTPS_transport.h"
|
||||
|
||||
@[for topic in list(set(topic_names))]@
|
||||
#include <uORB/topics/@(topic).h>
|
||||
@[end for]@
|
||||
|
||||
#define BUFFER_SIZE 1024
|
||||
#define UPDATE_TIME_MS 0
|
||||
#define LOOPS 10000
|
||||
#define SLEEP_MS 1
|
||||
#define BAUDRATE 460800
|
||||
#define DEVICE "/dev/ttyACM0"
|
||||
#define POLL_MS 1
|
||||
#define DEFAULT_RECV_PORT 2019
|
||||
#define DEFAULT_SEND_PORT 2020
|
||||
|
||||
extern "C" __EXPORT int micrortps_client_main(int argc, char *argv[]);
|
||||
void* send(void *data);
|
||||
|
||||
struct options {
|
||||
enum class eTransports
|
||||
{
|
||||
UART,
|
||||
UDP
|
||||
};
|
||||
eTransports transport = options::eTransports::UART;
|
||||
char device[64] = DEVICE;
|
||||
int update_time_ms = UPDATE_TIME_MS;
|
||||
int loops = LOOPS;
|
||||
int sleep_ms = SLEEP_MS;
|
||||
uint32_t baudrate = BAUDRATE;
|
||||
int poll_ms = POLL_MS;
|
||||
uint16_t recv_port = DEFAULT_RECV_PORT;
|
||||
uint16_t send_port = DEFAULT_SEND_PORT;
|
||||
} _options;
|
||||
|
||||
static int _rtps_task = -1;
|
||||
static bool _should_exit_task = false;
|
||||
Transport_node *transport_node = nullptr;
|
||||
|
||||
static void usage(const char *name)
|
||||
{
|
||||
PX4_INFO("usage: %s start|stop [options]\n\n"
|
||||
" -t <transport> [UART|UDP] Default UART\n"
|
||||
" -d <device> UART device. Default /dev/ttyACM0\n"
|
||||
" -u <update_time_ms> Time in ms for uORB subscribed topics update. Default 0\n"
|
||||
" -l <loops> How many iterations will this program have. -1 for infinite. Default 10000\n"
|
||||
" -w <sleep_time_ms> Time in ms for which each iteration sleep. Default 1ms\n"
|
||||
" -b <baudrate> UART device baudrate. Default 460800\n"
|
||||
" -p <poll_ms> Time in ms to poll over UART. Default 1ms\n"
|
||||
" -r <reception port> UDP port for receiving. Default 2019\n"
|
||||
" -s <sending port> UDP port for sending. Default 2020\n",
|
||||
name);
|
||||
}
|
||||
|
||||
static int parse_options(int argc, char *argv[])
|
||||
{
|
||||
int ch;
|
||||
int myoptind = 1;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "t:d:u:l:w:b:p:r:s:", &myoptind, &myoptarg)) != EOF)
|
||||
{
|
||||
switch (ch)
|
||||
{
|
||||
case 't': _options.transport = strcmp(myoptarg, "UDP") == 0?
|
||||
options::eTransports::UDP
|
||||
:options::eTransports::UART; break;
|
||||
case 'd': if (nullptr != myoptarg) strcpy(_options.device, myoptarg); break;
|
||||
case 'u': _options.update_time_ms = strtol(myoptarg, nullptr, 10); break;
|
||||
case 'l': _options.loops = strtol(myoptarg, nullptr, 10); break;
|
||||
case 'w': _options.sleep_ms = strtol(myoptarg, nullptr, 10); break;
|
||||
case 'b': _options.baudrate = strtoul(optarg, nullptr, 10); break;
|
||||
case 'p': _options.poll_ms = strtol(optarg, nullptr, 10); break;
|
||||
case 'r': _options.recv_port = strtoul(optarg, nullptr, 10); break;
|
||||
case 's': _options.send_port = strtoul(optarg, nullptr, 10); break;
|
||||
default:
|
||||
usage(argv[1]);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@[if send_topics]@
|
||||
void* send(void*)
|
||||
{
|
||||
char data_buffer[BUFFER_SIZE] = {};
|
||||
uint64_t sent = 0, total_sent = 0;
|
||||
int loop = 0, read = 0;
|
||||
uint32_t length = 0;
|
||||
|
||||
/* subscribe to topics */
|
||||
int fds[@(len(send_topics))] = {};
|
||||
|
||||
// orb_set_interval statblish an update interval period in milliseconds.
|
||||
@[for idx, topic in enumerate(send_topics)]@
|
||||
fds[@(idx)] = orb_subscribe(ORB_ID(@(topic)));
|
||||
orb_set_interval(fds[@(idx)], _options.update_time_ms);
|
||||
@[end for]@
|
||||
|
||||
// microBuffer to serialized using the user defined buffer
|
||||
struct microBuffer microBufferWriter;
|
||||
initStaticAlignedBuffer(data_buffer, BUFFER_SIZE, µBufferWriter);
|
||||
// microCDR structs for managing the microBuffer
|
||||
struct microCDR microCDRWriter;
|
||||
initMicroCDR(µCDRWriter, µBufferWriter);
|
||||
|
||||
struct timespec begin;
|
||||
clock_gettime(0, &begin);
|
||||
|
||||
while (!_should_exit_task)
|
||||
{
|
||||
bool updated;
|
||||
@[for idx, topic in enumerate(send_topics)]@
|
||||
orb_check(fds[@(idx)], &updated);
|
||||
if (updated)
|
||||
{
|
||||
// obtained data for the file descriptor
|
||||
struct @(topic)_s data = {};
|
||||
// copy raw data into local buffer
|
||||
orb_copy(ORB_ID(@(topic)), fds[@(idx)], &data);
|
||||
serialize_@(topic)(&data, data_buffer, &length, µCDRWriter);
|
||||
if (0 < (read = transport_node->write((char)@(message_id(topic)), data_buffer, length)))
|
||||
{
|
||||
total_sent += read;
|
||||
++sent;
|
||||
}
|
||||
}
|
||||
@[end for]@
|
||||
|
||||
usleep(_options.sleep_ms*1000);
|
||||
++loop;
|
||||
}
|
||||
|
||||
struct timespec end;
|
||||
clock_gettime(0, &end);
|
||||
double elapsed_secs = double(end.tv_sec - begin.tv_sec) + double(end.tv_nsec - begin.tv_nsec)/double(1000000000);
|
||||
printf("\nSENT: %lu messages in %d LOOPS, %llu bytes in %.03f seconds - %.02fKB/s\n",
|
||||
(unsigned long)sent, loop, total_sent, elapsed_secs, (double)total_sent/(1000*elapsed_secs));
|
||||
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
static int launch_send_thread(pthread_t &sender_thread)
|
||||
{
|
||||
pthread_attr_t sender_thread_attr;
|
||||
pthread_attr_init(&sender_thread_attr);
|
||||
pthread_attr_setstacksize(&sender_thread_attr, PX4_STACK_ADJUSTED(4000));
|
||||
struct sched_param param;
|
||||
(void)pthread_attr_getschedparam(&sender_thread_attr, ¶m);
|
||||
param.sched_priority = SCHED_PRIORITY_DEFAULT;
|
||||
(void)pthread_attr_setschedparam(&sender_thread_attr, ¶m);
|
||||
pthread_create(&sender_thread, &sender_thread_attr, send, nullptr);
|
||||
pthread_attr_destroy(&sender_thread_attr);
|
||||
|
||||
return 0;
|
||||
}
|
||||
@[end if]@
|
||||
|
||||
static int micrortps_start(int argc, char *argv[])
|
||||
{
|
||||
if (0 > parse_options(argc, argv))
|
||||
{
|
||||
printf("EXITING...\n");
|
||||
_rtps_task = -1;
|
||||
return -1;
|
||||
}
|
||||
|
||||
switch (_options.transport)
|
||||
{
|
||||
case options::eTransports::UART:
|
||||
{
|
||||
transport_node = new UART_node(_options.device, _options.baudrate, _options.poll_ms);
|
||||
printf("\nUART transport: device: %s; baudrate: %d; sleep: %dms; poll: %dms\n\n",
|
||||
_options.device, _options.baudrate, _options.sleep_ms, _options.poll_ms);
|
||||
}
|
||||
break;
|
||||
case options::eTransports::UDP:
|
||||
{
|
||||
transport_node = new UDP_node(_options.recv_port, _options.send_port);
|
||||
printf("\nUDP transport: recv port: %u; send port: %u; sleep: %dms\n\n",
|
||||
_options.recv_port, _options.send_port, _options.sleep_ms);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
_rtps_task = -1;
|
||||
printf("EXITING...\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (0 > transport_node->init())
|
||||
{
|
||||
printf("EXITING...\n");
|
||||
_rtps_task = -1;
|
||||
return -1;
|
||||
}
|
||||
|
||||
sleep(1);
|
||||
@[if recv_topics]@
|
||||
|
||||
char data_buffer[BUFFER_SIZE] = {};
|
||||
int read = 0;
|
||||
char topic_ID = 255;
|
||||
|
||||
// Declare received topics
|
||||
@[for topic in recv_topics]@
|
||||
struct @(topic)_s @(topic)_data;
|
||||
orb_advert_t @(topic)_pub = nullptr;
|
||||
@[end for]@
|
||||
|
||||
// microBuffer to deserialized using the user defined buffer
|
||||
struct microBuffer microBufferReader;
|
||||
initDeserializedAlignedBuffer(data_buffer, BUFFER_SIZE, µBufferReader);
|
||||
// microCDR structs for managing the microBuffer
|
||||
struct microCDR microCDRReader;
|
||||
initMicroCDR(µCDRReader, µBufferReader);
|
||||
@[end if]@
|
||||
|
||||
int total_read = 0;
|
||||
uint32_t received = 0;
|
||||
struct timespec begin;
|
||||
clock_gettime(0, &begin);
|
||||
int loop = 0;
|
||||
_should_exit_task = false;
|
||||
@[if send_topics]@
|
||||
|
||||
// create a thread for sending data to the simulator
|
||||
pthread_t sender_thread;
|
||||
launch_send_thread(sender_thread);
|
||||
@[end if]@
|
||||
|
||||
while (!_should_exit_task)
|
||||
{
|
||||
@[if recv_topics]@
|
||||
while (0 < (read = transport_node->read(&topic_ID, data_buffer, BUFFER_SIZE)))
|
||||
{
|
||||
total_read += read;
|
||||
switch (topic_ID)
|
||||
{
|
||||
@[for topic in recv_topics]@
|
||||
case @(message_id(topic)):
|
||||
{
|
||||
deserialize_@(topic)(&@(topic)_data, data_buffer, µCDRReader);
|
||||
if (!@(topic)_pub)
|
||||
@(topic)_pub = orb_advertise(ORB_ID(@(topic)), &@(topic)_data);
|
||||
else
|
||||
orb_publish(ORB_ID(@(topic)), @(topic)_pub, &@(topic)_data);
|
||||
++received;
|
||||
}
|
||||
break;
|
||||
@[end for]@
|
||||
default:
|
||||
printf("Unexpected topic ID\n");
|
||||
break;
|
||||
}
|
||||
}
|
||||
@[end if]@
|
||||
|
||||
// loop forever if informed loop number is negative
|
||||
if (_options.loops > 0 && loop >= _options.loops) break;
|
||||
|
||||
usleep(_options.sleep_ms*1000);
|
||||
++loop;
|
||||
}
|
||||
@[if send_topics]@
|
||||
_should_exit_task = true;
|
||||
pthread_join(sender_thread, 0);
|
||||
@[end if]@
|
||||
|
||||
struct timespec end;
|
||||
clock_gettime(0, &end);
|
||||
double elapsed_secs = double(end.tv_sec - begin.tv_sec) + double(end.tv_nsec - begin.tv_nsec)/double(1000000000);
|
||||
printf("RECEIVED: %lu messages in %d LOOPS, %d bytes in %.03f seconds - %.02fKB/s\n\n",
|
||||
(unsigned long)received, loop, total_read, elapsed_secs, (double)total_read/(1000*elapsed_secs));
|
||||
|
||||
delete transport_node;
|
||||
transport_node = nullptr;
|
||||
PX4_INFO("exiting");
|
||||
fflush(stdout);
|
||||
|
||||
_rtps_task = -1;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int micrortps_client_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2)
|
||||
{
|
||||
usage(argv[0]);
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start"))
|
||||
{
|
||||
if (_rtps_task != -1)
|
||||
{
|
||||
PX4_INFO("Already running");
|
||||
return -1;
|
||||
}
|
||||
|
||||
_rtps_task = px4_task_spawn_cmd("rtps",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
4096,
|
||||
(px4_main_t) micrortps_start,
|
||||
(char *const *)argv);
|
||||
|
||||
if (_rtps_task < 0)
|
||||
{
|
||||
PX4_WARN("Could not start task");
|
||||
_rtps_task = -1;
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop"))
|
||||
{
|
||||
if (_rtps_task == -1)
|
||||
{
|
||||
PX4_INFO("Not running");
|
||||
return -1;
|
||||
}
|
||||
|
||||
_should_exit_task = true;
|
||||
if (nullptr != transport_node) transport_node->close();
|
||||
return 0;
|
||||
}
|
||||
|
||||
usage(argv[0]);
|
||||
|
||||
return -1;
|
||||
}
|
||||
@@ -64,9 +64,11 @@ struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
|
||||
topic_fields = ["uint64_t timestamp"]+["%s %s" % (convert_type(field.type), field.name) for field in sorted_fields]
|
||||
}@
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <drivers/drv_orb_dev.h>
|
||||
#include <microcdr/microCdr.h>
|
||||
#include <uORB/topics/@(topic_name).h>
|
||||
|
||||
|
||||
@# join all msg files in one line e.g: "float[3] position;float[3] velocity;bool armed"
|
||||
@# This is used for the logger
|
||||
constexpr char __orb_@(topic_name)_fields[] = "@( ";".join(topic_fields) );";
|
||||
@@ -75,3 +77,99 @@ constexpr char __orb_@(topic_name)_fields[] = "@( ";".join(topic_fields) );";
|
||||
ORB_DEFINE(@multi_topic, struct @uorb_struct, @(struct_size-padding_end_size),
|
||||
__orb_@(topic_name)_fields);
|
||||
@[end for]
|
||||
|
||||
@#################################################
|
||||
@# Searching for serialize function per each field
|
||||
@#################################################
|
||||
@{
|
||||
|
||||
def print_info(field):
|
||||
print "type: ", field.type, "name: ", field.name, "base_type: ", \
|
||||
field.base_type, "field.is_array:", ('0', '1')[field.is_array], " array_len: ", field.array_len, \
|
||||
"is_builtin:", ('0', '1')[field.is_builtin], "is_header:", ('0', '1')[field.is_header]
|
||||
|
||||
def print_level_info(fields):
|
||||
for field in fields:
|
||||
print_info(field)
|
||||
if (not field.is_builtin):
|
||||
print "\n"
|
||||
children_fields = get_children_fields(field.base_type, search_path)
|
||||
print_level_info(children_fields)
|
||||
print "\n"
|
||||
|
||||
def walk_through_parsed_fields():
|
||||
print_level_info(spec.parsed_fields())
|
||||
|
||||
def get_serialization_type_name(type_name):
|
||||
if type_name in type_serialize_map:
|
||||
return type_serialize_map[type_name]
|
||||
else:
|
||||
raise Exception("Type {0} not supported, add to type_serialize_map!".format(type_name))
|
||||
|
||||
def add_serialize_functions(fields, scope_name):
|
||||
for field in fields:
|
||||
if (not field.is_header):
|
||||
if (field.is_builtin):
|
||||
if (not field.is_array):
|
||||
print "\tserialize"+str(get_serialization_type_name(field.type))+"(input->"+scope_name+str(field.name)+", microCDRWriter);"
|
||||
else:
|
||||
print "\tserialize"+str(get_serialization_type_name(field.base_type))+"Array(input->"+scope_name+str(field.name)+", "+str(field.array_len)+", microCDRWriter);"
|
||||
else:
|
||||
name = field.name
|
||||
children_fields = get_children_fields(field.base_type, search_path)
|
||||
if (scope_name): name = scope_name + name
|
||||
if (not field.is_array):
|
||||
add_serialize_functions(children_fields, name + '.')
|
||||
else:
|
||||
for i in xrange(field.array_len):
|
||||
add_serialize_functions(children_fields, name + ('[%d].' %i))
|
||||
|
||||
def add_deserialize_functions(fields, scope_name):
|
||||
for field in fields:
|
||||
if (not field.is_header):
|
||||
if (field.is_builtin):
|
||||
if (not field.is_array):
|
||||
print "\tdeserialize"+str(get_serialization_type_name(field.type))+"(&output->"+scope_name+str(field.name)+", microCDRReader);"
|
||||
else:
|
||||
for i in xrange(field.array_len):
|
||||
print "\tdeserialize"+str(get_serialization_type_name(field.base_type))+"(&output->"+scope_name+str(field.name)+ str('[%d]' %i) +", microCDRReader);"
|
||||
else:
|
||||
name = field.name
|
||||
children_fields = get_children_fields(field.base_type, search_path)
|
||||
if (scope_name): name = scope_name + name
|
||||
if (not field.is_array):
|
||||
add_deserialize_functions(children_fields, name + '.')
|
||||
else:
|
||||
for i in xrange(field.array_len):
|
||||
add_deserialize_functions(children_fields, name + ('[%d].' %i))
|
||||
|
||||
def add_code_to_serialize():
|
||||
# sort fields (using a stable sort) as in the declaration of the type
|
||||
sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True)
|
||||
add_serialize_functions(sorted_fields, "")
|
||||
|
||||
def add_code_to_deserialize():
|
||||
# sort fields (using a stable sort) as in the declaration of the type
|
||||
sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True)
|
||||
add_deserialize_functions(sorted_fields, "")
|
||||
}@
|
||||
|
||||
void serialize_@(topic_name)(const struct @(uorb_struct) *input, char *output, uint32_t *length, struct microCDR *microCDRWriter)
|
||||
{
|
||||
if (nullptr == input || nullptr == output || nullptr == length || nullptr == microCDRWriter) return;
|
||||
|
||||
resetStaticMicroCDRForSerialize(microCDRWriter);
|
||||
|
||||
@add_code_to_serialize()
|
||||
|
||||
(*length) = microCDRWriter->m_microBuffer->m_serializedBuffer;
|
||||
}
|
||||
|
||||
void deserialize_@(topic_name)(struct @(uorb_struct) *output, char *input, struct microCDR *microCDRReader)
|
||||
{
|
||||
if (nullptr == output || nullptr == input || nullptr == microCDRReader) return;
|
||||
|
||||
resetStaticMicroCDRForDeserialize(microCDRReader);
|
||||
|
||||
@add_code_to_deserialize()
|
||||
}
|
||||
@@ -108,6 +108,8 @@ def print_parsed_fields():
|
||||
print_field_def(field)
|
||||
}@
|
||||
|
||||
struct microCDR;
|
||||
|
||||
#ifdef __cplusplus
|
||||
@#class @(uorb_struct) {
|
||||
struct __EXPORT @(uorb_struct) {
|
||||
@@ -118,6 +120,7 @@ struct @(uorb_struct) {
|
||||
@# timestamp at the beginning of each topic is required for logger
|
||||
uint64_t timestamp; // required for logger
|
||||
@print_parsed_fields()
|
||||
|
||||
#ifdef __cplusplus
|
||||
@# Constants again c++-ified
|
||||
@{
|
||||
@@ -134,6 +137,10 @@ for constant in spec.constants:
|
||||
#endif
|
||||
};
|
||||
|
||||
|
||||
void serialize_@(topic_name)(const struct @(uorb_struct) *input, char *output, uint32_t *length, struct microCDR *microCDRWriter);
|
||||
void deserialize_@(topic_name)(struct @(uorb_struct) *output, char *input, struct microCDR *microCDRReader);
|
||||
|
||||
/* register this as object request broker structure */
|
||||
@[for multi_topic in topics]@
|
||||
ORB_DECLARE(@multi_topic);
|
||||
|
||||
@@ -0,0 +1,154 @@
|
||||
@###############################################
|
||||
@#
|
||||
@# EmPy template for generating <msg>_uRTPS_UART.cpp file
|
||||
@#
|
||||
@###############################################
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - msgs (List) list of all msg files
|
||||
@# - multi_topics (List) list of all multi-topic names
|
||||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import gencpp
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
topic = spec.short_name
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||||
*
|
||||
* 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 of the copyright holder 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 HOLDER 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*!
|
||||
* @@file @(topic)_Publisher.cpp
|
||||
* This file contains the implementation of the publisher functions.
|
||||
*
|
||||
* This file was generated by the tool fastcdrgen.
|
||||
*/
|
||||
|
||||
#include <fastrtps/participant/Participant.h>
|
||||
#include <fastrtps/attributes/ParticipantAttributes.h>
|
||||
#include <fastrtps/publisher/Publisher.h>
|
||||
#include <fastrtps/attributes/PublisherAttributes.h>
|
||||
|
||||
#include <fastrtps/Domain.h>
|
||||
|
||||
#include <fastrtps/utils/eClock.h>
|
||||
|
||||
#include "@(topic)_Publisher.h"
|
||||
|
||||
|
||||
@(topic)_Publisher::@(topic)_Publisher() : mp_participant(nullptr), mp_publisher(nullptr) {}
|
||||
|
||||
@(topic)_Publisher::~@(topic)_Publisher() { Domain::removeParticipant(mp_participant);}
|
||||
|
||||
bool @(topic)_Publisher::init()
|
||||
{
|
||||
// Create RTPSParticipant
|
||||
|
||||
ParticipantAttributes PParam;
|
||||
PParam.rtps.builtin.domainId = 0;
|
||||
PParam.rtps.builtin.leaseDuration = c_TimeInfinite;
|
||||
PParam.rtps.setName("Participant_publisher"); //You can put here the name you want
|
||||
mp_participant = Domain::createParticipant(PParam);
|
||||
if(mp_participant == nullptr)
|
||||
return false;
|
||||
|
||||
//Register the type
|
||||
|
||||
Domain::registerType(mp_participant,(TopicDataType*) &myType);
|
||||
|
||||
// Create Publisher
|
||||
|
||||
PublisherAttributes Wparam;
|
||||
Wparam.topic.topicKind = NO_KEY;
|
||||
Wparam.topic.topicDataType = myType.getName(); //This type MUST be registered
|
||||
Wparam.topic.topicName = "@(topic)_PubSubTopic";
|
||||
mp_publisher = Domain::createPublisher(mp_participant,Wparam,(PublisherListener*)&m_listener);
|
||||
if(mp_publisher == nullptr)
|
||||
return false;
|
||||
//std::cout << "Publisher created, waiting for Subscribers." << std::endl;
|
||||
return true;
|
||||
}
|
||||
|
||||
void @(topic)_Publisher::PubListener::onPublicationMatched(Publisher* pub,MatchingInfo& info)
|
||||
{
|
||||
if (info.status == MATCHED_MATCHING)
|
||||
{
|
||||
n_matched++;
|
||||
std::cout << "Publisher matched" << std::endl;
|
||||
}
|
||||
else
|
||||
{
|
||||
n_matched--;
|
||||
std::cout << "Publisher unmatched" << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
void @(topic)_Publisher::run()
|
||||
{
|
||||
while(m_listener.n_matched == 0)
|
||||
{
|
||||
eClock::my_sleep(250); // Sleep 250 ms
|
||||
}
|
||||
|
||||
// Publication code
|
||||
|
||||
@(topic)_ st;
|
||||
|
||||
/* Initialize your structure here */
|
||||
|
||||
int msgsent = 0;
|
||||
char ch = 'y';
|
||||
do
|
||||
{
|
||||
if(ch == 'y')
|
||||
{
|
||||
mp_publisher->write(&st); ++msgsent;
|
||||
std::cout << "Sending sample, count=" << msgsent << ", send another sample?(y-yes,n-stop): ";
|
||||
}
|
||||
else if(ch == 'n')
|
||||
{
|
||||
std::cout << "Stopping execution " << std::endl;
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "Command " << ch << " not recognized, please enter \"y/n\":";
|
||||
}
|
||||
}while(std::cin >> ch);
|
||||
}
|
||||
|
||||
void @(topic)_Publisher::publish(@(topic)_* st)
|
||||
{
|
||||
mp_publisher->write(st);
|
||||
}
|
||||
@@ -0,0 +1,92 @@
|
||||
@###############################################
|
||||
@#
|
||||
@# EmPy template for generating <msg>_uRTPS_UART.cpp file
|
||||
@#
|
||||
@###############################################
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - msgs (List) list of all msg files
|
||||
@# - multi_topics (List) list of all multi-topic names
|
||||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import gencpp
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
topic = spec.short_name
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||||
*
|
||||
* 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 of the copyright holder 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 HOLDER 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*!
|
||||
* @@file @(topic)_Publisher.h
|
||||
* This header file contains the declaration of the publisher functions.
|
||||
*
|
||||
* This file was generated by the tool fastcdrgen.
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _@(topic)__PUBLISHER_H_
|
||||
#define _@(topic)__PUBLISHER_H_
|
||||
|
||||
#include <fastrtps/fastrtps_fwd.h>
|
||||
#include <fastrtps/publisher/PublisherListener.h>
|
||||
|
||||
#include "@(topic)_PubSubTypes.h"
|
||||
|
||||
using namespace eprosima::fastrtps;
|
||||
|
||||
class @(topic)_Publisher
|
||||
{
|
||||
public:
|
||||
@(topic)_Publisher();
|
||||
virtual ~@(topic)_Publisher();
|
||||
bool init();
|
||||
void run();
|
||||
void publish(@(topic)_* st);
|
||||
private:
|
||||
Participant *mp_participant;
|
||||
Publisher *mp_publisher;
|
||||
|
||||
class PubListener : public PublisherListener
|
||||
{
|
||||
public:
|
||||
PubListener() : n_matched(0){};
|
||||
~PubListener(){};
|
||||
void onPublicationMatched(Publisher* pub,MatchingInfo& info);
|
||||
int n_matched;
|
||||
} m_listener;
|
||||
@(topic)_PubSubType myType;
|
||||
};
|
||||
|
||||
#endif // _@(topic)__PUBLISHER_H_
|
||||
@@ -0,0 +1,159 @@
|
||||
@###############################################
|
||||
@#
|
||||
@# EmPy template for generating RtpsTopics.cxx file
|
||||
@#
|
||||
@###############################################
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - msgs (List) list of all msg files
|
||||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import gencpp
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
from message_id import * # 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]
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||||
*
|
||||
* 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 of the copyright holder 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 HOLDER 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "RtpsTopics.h"
|
||||
|
||||
bool RtpsTopics::init()
|
||||
{
|
||||
@[if recv_topics]@
|
||||
// Initialise subscribers
|
||||
@[for topic in recv_topics]@
|
||||
if (_@(topic)_sub.init()) {
|
||||
std::cout << "@(topic) subscriber started" << std::endl;
|
||||
} else {
|
||||
std::cout << "ERROR starting @(topic) subscriber" << std::endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
@[end for]@
|
||||
@[end if]@
|
||||
@[if send_topics]@
|
||||
// Initialise publishers
|
||||
@[for topic in send_topics]@
|
||||
if (_@(topic)_pub.init()) {
|
||||
std::cout << "@(topic) publisher started" << std::endl;
|
||||
} else {
|
||||
std::cout << "ERROR starting @(topic) publisher" << std::endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
@[end for]@
|
||||
@[end if]@
|
||||
return true;
|
||||
}
|
||||
|
||||
@[if send_topics]@
|
||||
void RtpsTopics::publish(char topic_ID, char data_buffer[], size_t len)
|
||||
{
|
||||
switch (topic_ID)
|
||||
{
|
||||
@[for topic in send_topics]@
|
||||
case @(message_id(topic)): // @(topic)
|
||||
{
|
||||
@(topic)_ st;
|
||||
eprosima::fastcdr::FastBuffer cdrbuffer(data_buffer, len);
|
||||
eprosima::fastcdr::Cdr cdr_des(cdrbuffer);
|
||||
st.deserialize(cdr_des);
|
||||
_@(topic)_pub.publish(&st);
|
||||
}
|
||||
break;
|
||||
@[end for]@
|
||||
default:
|
||||
printf("Unexpected topic ID to publish\n");
|
||||
break;
|
||||
}
|
||||
}
|
||||
@[end if]@
|
||||
@[if recv_topics]@
|
||||
|
||||
bool RtpsTopics::hasMsg(char *topic_ID)
|
||||
{
|
||||
if (nullptr == topic_ID) return false;
|
||||
|
||||
*topic_ID = 0;
|
||||
while (_next_sub_idx < @(len(recv_topics)) && 0 == *topic_ID)
|
||||
{
|
||||
switch (_sub_topics[_next_sub_idx])
|
||||
{
|
||||
@[for topic in recv_topics]@
|
||||
case @(message_id(topic)): if (_@(topic)_sub.hasMsg()) *topic_ID = @(message_id(topic)); break;
|
||||
@[end for]@
|
||||
default:
|
||||
printf("Unexpected topic ID to check hasMsg\n");
|
||||
break;
|
||||
}
|
||||
_next_sub_idx++;
|
||||
}
|
||||
|
||||
if (0 == *topic_ID)
|
||||
{
|
||||
_next_sub_idx = 0;
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool RtpsTopics::getMsg(const char topic_ID, eprosima::fastcdr::Cdr &scdr)
|
||||
{
|
||||
bool ret = false;
|
||||
switch (topic_ID)
|
||||
{
|
||||
@[for topic in recv_topics]@
|
||||
case @(message_id(topic)): // @(topic)
|
||||
if (_@(topic)_sub.hasMsg())
|
||||
{
|
||||
@(topic)_ msg = _@(topic)_sub.getMsg();
|
||||
msg.serialize(scdr);
|
||||
ret = true;
|
||||
}
|
||||
break;
|
||||
@[end for]@
|
||||
default:
|
||||
printf("Unexpected topic ID '%hhu' to getMsg\n", topic_ID);
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
@[end if]@
|
||||
@@ -0,0 +1,95 @@
|
||||
@###############################################
|
||||
@#
|
||||
@# EmPy template for generating RtpsTopics.h file
|
||||
@#
|
||||
@###############################################
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - msgs (List) list of all msg files
|
||||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import gencpp
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||||
from message_id import * # 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]
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||||
*
|
||||
* 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 of the copyright holder 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 HOLDER 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <fastcdr/Cdr.h>
|
||||
|
||||
@[for topic in send_topics]@
|
||||
#include "@(topic)_Publisher.h"
|
||||
@[end for]@
|
||||
@[for topic in recv_topics]@
|
||||
#include "@(topic)_Subscriber.h"
|
||||
@[end for]@
|
||||
|
||||
class RtpsTopics {
|
||||
public:
|
||||
bool init();
|
||||
@[if send_topics]@
|
||||
void publish(char topic_ID, char data_buffer[], size_t len);
|
||||
@[end if]@
|
||||
@[if recv_topics]@
|
||||
bool hasMsg(char *topic_ID);
|
||||
bool getMsg(const char topic_ID, eprosima::fastcdr::Cdr &scdr);
|
||||
@[end if]@
|
||||
|
||||
private:
|
||||
@[if send_topics]@
|
||||
// Publishers
|
||||
@[for topic in send_topics]@
|
||||
@(topic)_Publisher _@(topic)_pub;
|
||||
@[end for]@
|
||||
@[end if]@
|
||||
|
||||
@[if recv_topics]@
|
||||
// Subscribers
|
||||
@[for topic in recv_topics]@
|
||||
@(topic)_Subscriber _@(topic)_sub;
|
||||
@[end for]@
|
||||
|
||||
unsigned _next_sub_idx = 0;
|
||||
char _sub_topics[@(len(recv_topics))] = {
|
||||
@[for topic in recv_topics]@
|
||||
@(message_id(topic)), // @(topic)
|
||||
@[end for]@
|
||||
};
|
||||
@[end if]@
|
||||
};
|
||||
@@ -0,0 +1,146 @@
|
||||
@###############################################
|
||||
@#
|
||||
@# EmPy template for generating <msg>_uRTPS_UART.cpp file
|
||||
@#
|
||||
@###############################################
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - msgs (List) list of all msg files
|
||||
@# - multi_topics (List) list of all multi-topic names
|
||||
@###############################################
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import gencpp
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
topic = spec.short_name
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||||
*
|
||||
* 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 of the copyright holder 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 HOLDER 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*!
|
||||
* @@file @(topic)_Subscriber.cpp
|
||||
* This file contains the implementation of the subscriber functions.
|
||||
*
|
||||
* This file was generated by the tool fastcdrgen.
|
||||
*/
|
||||
|
||||
#include <fastrtps/participant/Participant.h>
|
||||
#include <fastrtps/attributes/ParticipantAttributes.h>
|
||||
#include <fastrtps/subscriber/Subscriber.h>
|
||||
#include <fastrtps/attributes/SubscriberAttributes.h>
|
||||
|
||||
#include <fastrtps/Domain.h>
|
||||
|
||||
#include "@(topic)_Subscriber.h"
|
||||
|
||||
|
||||
@(topic)_Subscriber::@(topic)_Subscriber() : mp_participant(nullptr), mp_subscriber(nullptr) {}
|
||||
|
||||
@(topic)_Subscriber::~@(topic)_Subscriber() { Domain::removeParticipant(mp_participant);}
|
||||
|
||||
bool @(topic)_Subscriber::init()
|
||||
{
|
||||
// Create RTPSParticipant
|
||||
|
||||
ParticipantAttributes PParam;
|
||||
PParam.rtps.builtin.domainId = 0; //MUST BE THE SAME AS IN THE PUBLISHER
|
||||
PParam.rtps.builtin.leaseDuration = c_TimeInfinite;
|
||||
PParam.rtps.setName("Participant_subscriber"); //You can put the name you want
|
||||
mp_participant = Domain::createParticipant(PParam);
|
||||
if(mp_participant == nullptr)
|
||||
return false;
|
||||
|
||||
//Register the type
|
||||
|
||||
Domain::registerType(mp_participant,(TopicDataType*) &myType);
|
||||
|
||||
// Create Subscriber
|
||||
|
||||
SubscriberAttributes Rparam;
|
||||
Rparam.topic.topicKind = NO_KEY;
|
||||
Rparam.topic.topicDataType = myType.getName(); //Must be registered before the creation of the subscriber
|
||||
Rparam.topic.topicName = "@(topic)_PubSubTopic";
|
||||
mp_subscriber = Domain::createSubscriber(mp_participant,Rparam,(SubscriberListener*)&m_listener);
|
||||
if(mp_subscriber == nullptr)
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
|
||||
void @(topic)_Subscriber::SubListener::onSubscriptionMatched(Subscriber* sub,MatchingInfo& info)
|
||||
{
|
||||
if (info.status == MATCHED_MATCHING)
|
||||
{
|
||||
n_matched++;
|
||||
std::cout << "Subscriber matched" << std::endl;
|
||||
}
|
||||
else
|
||||
{
|
||||
n_matched--;
|
||||
std::cout << "Subscriber unmatched" << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
void @(topic)_Subscriber::SubListener::onNewDataMessage(Subscriber* sub)
|
||||
{
|
||||
// Take data
|
||||
if(sub->takeNextData(&msg, &m_info))
|
||||
{
|
||||
if(m_info.sampleKind == ALIVE)
|
||||
{
|
||||
// Print your structure data here.
|
||||
++n_msg;
|
||||
//std::cout << "Sample received, count=" << n_msg << std::endl;
|
||||
has_msg = true;
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void @(topic)_Subscriber::run()
|
||||
{
|
||||
std::cout << "Waiting for Data, press Enter to stop the Subscriber. "<<std::endl;
|
||||
std::cin.ignore();
|
||||
std::cout << "Shutting down the Subscriber." << std::endl;
|
||||
}
|
||||
|
||||
bool @(topic)_Subscriber::hasMsg()
|
||||
{
|
||||
return m_listener.has_msg;
|
||||
}
|
||||
|
||||
@(topic)_ @(topic)_Subscriber::getMsg()
|
||||
{
|
||||
m_listener.has_msg = false;
|
||||
return m_listener.msg;
|
||||
}
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user