forked from Archive/PX4-Autopilot
load RTPS msg IDs from a JSON file and remove uorb_rtps_message_ids.py
This commit is contained in:
parent
943bfbf93f
commit
a323073456
|
@ -9,11 +9,12 @@
|
|||
@# - msgs (List) list of all msg files
|
||||
@###############################################
|
||||
@{
|
||||
import os
|
||||
|
||||
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 uorb_rtps_message_ids 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]
|
||||
|
@ -88,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 @(message_id(topic)): // @(topic)
|
||||
case @(rtps_message_id(os.path.abspath('uorb_rtps_message_ids.json'), topic)): // @(topic)
|
||||
{
|
||||
@(topic)_ st;
|
||||
eprosima::fastcdr::FastBuffer cdrbuffer(data_buffer, len);
|
||||
|
@ -116,7 +117,7 @@ bool RtpsTopics::hasMsg(uint8_t *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;
|
||||
case @(rtps_message_id(os.path.abspath('uorb_rtps_message_ids.json'), topic)): if (_@(topic)_sub.hasMsg()) *topic_ID = @(rtps_message_id(os.path.abspath('uorb_rtps_message_ids.json'), topic)); break;
|
||||
@[end for]@
|
||||
default:
|
||||
printf("Unexpected topic ID to check hasMsg\n");
|
||||
|
@ -140,7 +141,7 @@ bool RtpsTopics::getMsg(const uint8_t topic_ID, eprosima::fastcdr::Cdr &scdr)
|
|||
switch (topic_ID)
|
||||
{
|
||||
@[for topic in recv_topics]@
|
||||
case @(message_id(topic)): // @(topic)
|
||||
case @(rtps_message_id(os.path.abspath('uorb_rtps_message_ids.json'), topic)): // @(topic)
|
||||
if (_@(topic)_sub.hasMsg())
|
||||
{
|
||||
@(topic)_ msg = _@(topic)_sub.getMsg();
|
||||
|
|
|
@ -9,11 +9,12 @@
|
|||
@# - msgs (List) list of all msg files
|
||||
@###############################################
|
||||
@{
|
||||
import os
|
||||
|
||||
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 uorb_rtps_message_ids 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]
|
||||
|
@ -88,7 +89,7 @@ private:
|
|||
unsigned _next_sub_idx = 0;
|
||||
char _sub_topics[@(len(recv_topics))] = {
|
||||
@[for topic in recv_topics]@
|
||||
@(message_id(topic)), // @(topic)
|
||||
@(rtps_message_id(os.path.abspath('uorb_rtps_message_ids.json'), topic)), // @(topic)
|
||||
@[end for]@
|
||||
};
|
||||
@[end if]@
|
||||
|
|
|
@ -14,7 +14,6 @@ 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 uorb_rtps_message_ids 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]
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
# Another positive effect of having the code here, is that this file will get
|
||||
# precompiled and thus message generation will be much faster
|
||||
|
||||
import json
|
||||
|
||||
import genmsg.msgs
|
||||
import gencpp
|
||||
|
@ -296,3 +297,15 @@ def print_field_def(field):
|
|||
|
||||
print('\t%s%s%s %s%s;%s'%(type_prefix, type_px4, type_appendix, field.name,
|
||||
array_size, comment))
|
||||
|
||||
def rtps_message_id(json_file, message):
|
||||
"""
|
||||
Get RTPS ID of uORB message
|
||||
"""
|
||||
with open(json_file, 'r') as f:
|
||||
msg_id_map = json.load(f)
|
||||
|
||||
for dict in msg_id_map["rtps"]:
|
||||
if message in dict["msg"]:
|
||||
return dict["id"]
|
||||
return 0
|
||||
|
|
|
@ -0,0 +1,352 @@
|
|||
{
|
||||
"rtps": [
|
||||
{
|
||||
"msg": "actuator_armed",
|
||||
"id": 1
|
||||
},
|
||||
{
|
||||
"msg": "actuator_controls",
|
||||
"id": 2
|
||||
},
|
||||
{
|
||||
"msg": "actuator_direct",
|
||||
"id": 3
|
||||
},
|
||||
{
|
||||
"msg": "actuator_outputs",
|
||||
"id": 4
|
||||
},
|
||||
{
|
||||
"msg": "adc_report",
|
||||
"id": 5
|
||||
},
|
||||
{
|
||||
"msg": "airspeed",
|
||||
"id": 6
|
||||
},
|
||||
{
|
||||
"msg": "att_pos_mocap",
|
||||
"id": 7
|
||||
},
|
||||
{
|
||||
"msg": "battery_status",
|
||||
"id": 8
|
||||
},
|
||||
{
|
||||
"msg": "camera_capture",
|
||||
"id": 9
|
||||
},
|
||||
{
|
||||
"msg": "camera_trigger",
|
||||
"id": 10
|
||||
},
|
||||
{
|
||||
"msg": "collision_report",
|
||||
"id": 11
|
||||
},
|
||||
{
|
||||
"msg": "commander_state",
|
||||
"id": 12
|
||||
},
|
||||
{
|
||||
"msg": "cpuload",
|
||||
"id": 14
|
||||
},
|
||||
{
|
||||
"msg": "debug_key_value",
|
||||
"id": 15
|
||||
},
|
||||
{
|
||||
"msg": "differential_pressure",
|
||||
"id": 16
|
||||
},
|
||||
{
|
||||
"msg": "distance_sensor",
|
||||
"id": 17
|
||||
},
|
||||
{
|
||||
"msg": "ekf2_innovations",
|
||||
"id": 18
|
||||
},
|
||||
{
|
||||
"msg": "ekf2_timestamps",
|
||||
"id": 20
|
||||
},
|
||||
{
|
||||
"msg": "esc_report",
|
||||
"id": 21
|
||||
},
|
||||
{
|
||||
"msg": "esc_status",
|
||||
"id": 22
|
||||
},
|
||||
{
|
||||
"msg": "estimator_status",
|
||||
"id": 23
|
||||
},
|
||||
{
|
||||
"msg": "fence",
|
||||
"id": 24
|
||||
},
|
||||
{
|
||||
"msg": "fence_vertex",
|
||||
"id": 25
|
||||
},
|
||||
{
|
||||
"msg": "follow_target",
|
||||
"id": 27
|
||||
},
|
||||
{
|
||||
"msg": "fw_pos_ctrl_status",
|
||||
"id": 28
|
||||
},
|
||||
{
|
||||
"msg": "geofence_result",
|
||||
"id": 29
|
||||
},
|
||||
{
|
||||
"msg": "gps_dump",
|
||||
"id": 30
|
||||
},
|
||||
{
|
||||
"msg": "gps_inject_data",
|
||||
"id": 31
|
||||
},
|
||||
{
|
||||
"msg": "home_position",
|
||||
"id": 33
|
||||
},
|
||||
{
|
||||
"msg": "input_rc",
|
||||
"id": 34
|
||||
},
|
||||
{
|
||||
"msg": "led_control",
|
||||
"id": 35
|
||||
},
|
||||
{
|
||||
"msg": "log_message",
|
||||
"id": 36
|
||||
},
|
||||
{
|
||||
"msg": "manual_control_setpoint",
|
||||
"id": 37
|
||||
},
|
||||
{
|
||||
"msg": "mavlink_log",
|
||||
"id": 38
|
||||
},
|
||||
{
|
||||
"msg": "mc_att_ctrl_status",
|
||||
"id": 39
|
||||
},
|
||||
{
|
||||
"msg": "mission",
|
||||
"id": 40
|
||||
},
|
||||
{
|
||||
"msg": "mission_result",
|
||||
"id": 41
|
||||
},
|
||||
{
|
||||
"msg": "mount_orientation",
|
||||
"id": 42
|
||||
},
|
||||
{
|
||||
"msg": "multirotor_motor_limits",
|
||||
"id": 43
|
||||
},
|
||||
{
|
||||
"msg": "offboard_control_mode",
|
||||
"id": 44
|
||||
},
|
||||
{
|
||||
"msg": "optical_flow",
|
||||
"id": 45
|
||||
},
|
||||
{
|
||||
"msg": "parameter_update",
|
||||
"id": 47
|
||||
},
|
||||
{
|
||||
"msg": "position_setpoint",
|
||||
"id": 48
|
||||
},
|
||||
{
|
||||
"msg": "position_setpoint_triplet",
|
||||
"id": 49
|
||||
},
|
||||
{
|
||||
"msg": "pwm_input",
|
||||
"id": 40
|
||||
},
|
||||
{
|
||||
"msg": "qshell_req",
|
||||
"id": 51
|
||||
},
|
||||
{
|
||||
"msg": "rc_channels",
|
||||
"id": 52
|
||||
},
|
||||
{
|
||||
"msg": "rc_parameter_map",
|
||||
"id": 53
|
||||
},
|
||||
{
|
||||
"msg": "safety",
|
||||
"id": 54
|
||||
},
|
||||
{
|
||||
"msg": "satellite_info",
|
||||
"id": 55
|
||||
},
|
||||
{
|
||||
"msg": "sensor_accel",
|
||||
"id": 56
|
||||
},
|
||||
{
|
||||
"msg": "sensor_baro",
|
||||
"id": 57
|
||||
},
|
||||
{
|
||||
"msg": "sensor_combined",
|
||||
"id": 58
|
||||
},
|
||||
{
|
||||
"msg": "sensor_correction",
|
||||
"id": 59
|
||||
},
|
||||
{
|
||||
"msg": "sensor_gyro",
|
||||
"id": 60
|
||||
},
|
||||
{
|
||||
"msg": "sensor_mag",
|
||||
"id": 61
|
||||
},
|
||||
{
|
||||
"msg": "sensor_preflight",
|
||||
"id": 62
|
||||
},
|
||||
{
|
||||
"msg": "sensor_selection",
|
||||
"id": 63
|
||||
},
|
||||
{
|
||||
"msg": "servorail_status",
|
||||
"id": 64
|
||||
},
|
||||
{
|
||||
"msg": "subsystem_info",
|
||||
"id": 65
|
||||
},
|
||||
{
|
||||
"msg": "system_power",
|
||||
"id": 66
|
||||
},
|
||||
{
|
||||
"msg": "task_stack_info",
|
||||
"id": 67
|
||||
},
|
||||
{
|
||||
"msg": "tecs_status",
|
||||
"id": 68
|
||||
},
|
||||
{
|
||||
"msg": "telemetry_status",
|
||||
"id": 69
|
||||
},
|
||||
{
|
||||
"msg": "test_motor",
|
||||
"id": 70
|
||||
},
|
||||
{
|
||||
"msg": "time_offset",
|
||||
"id": 71
|
||||
},
|
||||
{
|
||||
"msg": "transponder_report",
|
||||
"id": 72
|
||||
},
|
||||
{
|
||||
"msg": "uavcan_parameter_request",
|
||||
"id": 73
|
||||
},
|
||||
{
|
||||
"msg": "uavcan_parameter_value",
|
||||
"id": 74
|
||||
},
|
||||
{
|
||||
"msg": "ulog_stream_ack",
|
||||
"id": 75
|
||||
},
|
||||
{
|
||||
"msg": "ulog_stream",
|
||||
"id": 76
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_attitude",
|
||||
"id": 77
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_attitude_setpoint",
|
||||
"id": 78
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_command_ack",
|
||||
"id": 79
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_command",
|
||||
"id": 80
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_control_mode",
|
||||
"id": 81
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_global_position",
|
||||
"id": 83
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_gps_position",
|
||||
"id": 85
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_land_detected",
|
||||
"id": 86
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_local_position",
|
||||
"id": 87
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_local_position_setpoint",
|
||||
"id": 88
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_rates_setpoint",
|
||||
"id": 89
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_roi",
|
||||
"id": 90
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_status_flags",
|
||||
"id": 91
|
||||
},
|
||||
{
|
||||
"msg": "vehicle_status",
|
||||
"id": 92
|
||||
},
|
||||
{
|
||||
"msg": "vtol_vehicle_status",
|
||||
"id": 93
|
||||
},
|
||||
{
|
||||
"msg": "wind_estimate",
|
||||
"id": 94
|
||||
}
|
||||
]
|
||||
}
|
|
@ -1,108 +0,0 @@
|
|||
|
||||
# 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,
|
||||
|
||||
'cpuload': 14,
|
||||
'debug_key_value': 15,
|
||||
'differential_pressure': 16,
|
||||
'distance_sensor': 17,
|
||||
'ekf2_innovations': 18,
|
||||
|
||||
'ekf2_timestamps': 20,
|
||||
'esc_report': 21,
|
||||
'esc_status': 22,
|
||||
'estimator_status': 23,
|
||||
'fence': 24,
|
||||
'fence_vertex': 25,
|
||||
|
||||
'follow_target': 27,
|
||||
'fw_pos_ctrl_status': 28,
|
||||
'geofence_result': 29,
|
||||
'gps_dump': 30,
|
||||
'gps_inject_data': 31,
|
||||
|
||||
'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,
|
||||
|
||||
'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_global_position': 83,
|
||||
|
||||
'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
|
|
@ -71,6 +71,10 @@ if (NOT "${config_rtps_send_topics}" STREQUAL "" OR NOT "${config_rtps_receive_t
|
|||
${msg_out_path}/micrortps_client/microRTPS_transport.h
|
||||
)
|
||||
|
||||
# Copy json 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.json"
|
||||
"${CMAKE_CURRENT_BINARY_DIR}/uorb_rtps_message_ids.json" 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}
|
||||
|
|
Loading…
Reference in New Issue